2009-12-08 10:28:54

by Pavel Machek

[permalink] [raw]
Subject: GPIO support for HTC Dream

Add GPIO support for HTC Dream.

Signed-off-by: Pavel Machek <[email protected]>

diff --git a/arch/arm/mach-msm/Kconfig b/arch/arm/mach-msm/Kconfig
index f780086..774c50e 100644
--- a/arch/arm/mach-msm/Kconfig
+++ b/arch/arm/mach-msm/Kconfig
@@ -40,4 +40,8 @@ config MACH_TROUT
help
Support for the HTC Dream, T-Mobile G1, Android ADP1 devices.

+config GENERIC_GPIO
+ bool
+ default y
+
endif
diff --git a/arch/arm/mach-msm/Makefile b/arch/arm/mach-msm/Makefile
index 91e6f5c..4c2567e 100644
--- a/arch/arm/mach-msm/Makefile
+++ b/arch/arm/mach-msm/Makefile
@@ -6,4 +6,4 @@ obj-y += clock.o clock-7x01a.o

obj-$(CONFIG_MACH_HALIBUT) += board-halibut.o

-obj-$(CONFIG_MACH_TROUT) += board-dream.o
+obj-$(CONFIG_MACH_TROUT) += board-dream.o board-dream-gpio.o generic_gpio.o
diff --git a/arch/arm/mach-msm/board-dream-gpio.c b/arch/arm/mach-msm/board-dream-gpio.c
new file mode 100644
index 0000000..1b23a84
--- /dev/null
+++ b/arch/arm/mach-msm/board-dream-gpio.c
@@ -0,0 +1,301 @@
+/* arch/arm/mach-msm/board-dream-gpio.c
+ *
+ * Copyright (C) 2008 Google, Inc.
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that 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/kernel.h>
+#include <linux/errno.h>
+#include <linux/irq.h>
+#include <linux/pm.h>
+#include <linux/sysdev.h>
+#include <linux/io.h>
+
+#include <asm/gpio.h>
+#include <asm/mach-types.h>
+
+#include "board-dream.h"
+#include "gpio_chip.h"
+
+#undef MODULE_PARAM_PREFIX
+#define MODULE_PARAM_PREFIX "board_dream."
+
+static uint cpld_usb_h2w_sw;
+module_param_named(usb_h2w_sw, cpld_usb_h2w_sw, uint, 0);
+
+static uint8_t dream_cpld_shadow[4] = {
+#if defined(CONFIG_MSM_DEBUG_UART1)
+ /* H2W pins <-> UART1 */
+ [0] = 0x40, // for serial debug, low current
+#else
+ /* H2W pins <-> UART3, Bluetooth <-> UART1 */
+ [0] = 0x80, // for serial debug, low current
+#endif
+ [1] = 0x04, // I2C_PULL
+ [3] = 0x04, // mmdi 32k en
+};
+static uint8_t dream_int_mask[2] = {
+ [0] = 0xff, /* mask all interrupts */
+ [1] = 0xff,
+};
+static uint8_t dream_sleep_int_mask[] = {
+ [0] = 0xff,
+ [1] = 0xff,
+};
+static int dream_suspended;
+
+static int dream_gpio_read(struct gpio_chip *chip, unsigned n)
+{
+ uint8_t b;
+ int reg;
+ if (n >= DREAM_GPIO_VIRTUAL_BASE)
+ n += DREAM_GPIO_VIRTUAL_TO_REAL_OFFSET;
+ b = 1U << (n & 7);
+ reg = (n & 0x78) >> 2; // assumes base is 128
+ return !!(readb(DREAM_CPLD_BASE + reg) & b);
+}
+
+static void update_pwrsink(unsigned gpio, unsigned on)
+{
+ switch(gpio) {
+ case DREAM_GPIO_UI_LED_EN:
+ break;
+ case DREAM_GPIO_QTKEY_LED_EN:
+ break;
+ }
+}
+
+static uint8_t dream_gpio_write_shadow(unsigned n, unsigned on)
+{
+ uint8_t b = 1U << (n & 7);
+ int reg = (n & 0x78) >> 2; // assumes base is 128
+
+ if(on)
+ return dream_cpld_shadow[reg >> 1] |= b;
+ else
+ return dream_cpld_shadow[reg >> 1] &= ~b;
+}
+
+static int dream_gpio_write(struct gpio_chip *chip, unsigned n, unsigned on)
+{
+ int reg = (n & 0x78) >> 2; // assumes base is 128
+ unsigned long flags;
+ uint8_t reg_val;
+
+ if ((reg >> 1) >= ARRAY_SIZE(dream_cpld_shadow)) {
+ printk(KERN_ERR "dream_gpio_write called on input %d\n", n);
+ return -ENOTSUPP;
+ }
+
+ local_irq_save(flags);
+ update_pwrsink(n, on);
+ reg_val = dream_gpio_write_shadow(n, on);
+ writeb(reg_val, DREAM_CPLD_BASE + reg);
+ local_irq_restore(flags);
+ return 0;
+}
+
+static int dream_gpio_configure(struct gpio_chip *chip, unsigned int gpio, unsigned long flags)
+{
+ if(flags & (GPIOF_OUTPUT_LOW | GPIOF_OUTPUT_HIGH))
+ dream_gpio_write(chip, gpio, flags & GPIOF_OUTPUT_HIGH);
+ return 0;
+}
+
+static int dream_gpio_get_irq_num(struct gpio_chip *chip, unsigned int gpio, unsigned int *irqp, unsigned long *irqnumflagsp)
+{
+ if ((gpio < DREAM_GPIO_BANK0_FIRST_INT_SOURCE ||
+ gpio > DREAM_GPIO_BANK0_LAST_INT_SOURCE) &&
+ (gpio < DREAM_GPIO_BANK1_FIRST_INT_SOURCE ||
+ gpio > DREAM_GPIO_BANK1_LAST_INT_SOURCE))
+ return -ENOENT;
+ *irqp = DREAM_GPIO_TO_INT(gpio);
+ if(irqnumflagsp)
+ *irqnumflagsp = 0;
+ return 0;
+}
+
+static void dream_gpio_irq_ack(unsigned int irq)
+{
+ int bank = DREAM_INT_TO_BANK(irq);
+ uint8_t mask = DREAM_INT_TO_MASK(irq);
+ int reg = DREAM_BANK_TO_STAT_REG(bank);
+ /*printk(KERN_INFO "dream_gpio_irq_ack irq %d\n", irq);*/
+ writeb(mask, DREAM_CPLD_BASE + reg);
+}
+
+static void dream_gpio_irq_mask(unsigned int irq)
+{
+ unsigned long flags;
+ uint8_t reg_val;
+ int bank = DREAM_INT_TO_BANK(irq);
+ uint8_t mask = DREAM_INT_TO_MASK(irq);
+ int reg = DREAM_BANK_TO_MASK_REG(bank);
+
+ local_irq_save(flags);
+ reg_val = dream_int_mask[bank] |= mask;
+ /*printk(KERN_INFO "dream_gpio_irq_mask irq %d => %d:%02x\n",
+ irq, bank, reg_val);*/
+ if (!dream_suspended)
+ writeb(reg_val, DREAM_CPLD_BASE + reg);
+ local_irq_restore(flags);
+}
+
+static void dream_gpio_irq_unmask(unsigned int irq)
+{
+ unsigned long flags;
+ uint8_t reg_val;
+ int bank = DREAM_INT_TO_BANK(irq);
+ uint8_t mask = DREAM_INT_TO_MASK(irq);
+ int reg = DREAM_BANK_TO_MASK_REG(bank);
+
+ local_irq_save(flags);
+ reg_val = dream_int_mask[bank] &= ~mask;
+ /*printk(KERN_INFO "dream_gpio_irq_unmask irq %d => %d:%02x\n",
+ irq, bank, reg_val);*/
+ if (!dream_suspended)
+ writeb(reg_val, DREAM_CPLD_BASE + reg);
+ local_irq_restore(flags);
+}
+
+int dream_gpio_irq_set_wake(unsigned int irq, unsigned int on)
+{
+ unsigned long flags;
+ int bank = DREAM_INT_TO_BANK(irq);
+ uint8_t mask = DREAM_INT_TO_MASK(irq);
+
+ local_irq_save(flags);
+ if(on)
+ dream_sleep_int_mask[bank] &= ~mask;
+ else
+ dream_sleep_int_mask[bank] |= mask;
+ local_irq_restore(flags);
+ return 0;
+}
+
+static void dream_gpio_irq_handler(unsigned int irq, struct irq_desc *desc)
+{
+ int j, m;
+ unsigned v;
+ int bank;
+ int stat_reg;
+ int int_base = DREAM_INT_START;
+ uint8_t int_mask;
+
+ for (bank = 0; bank < 2; bank++) {
+ stat_reg = DREAM_BANK_TO_STAT_REG(bank);
+ v = readb(DREAM_CPLD_BASE + stat_reg);
+ int_mask = dream_int_mask[bank];
+ if (v & int_mask) {
+ writeb(v & int_mask, DREAM_CPLD_BASE + stat_reg);
+ printk(KERN_ERR "dream_gpio_irq_handler: got masked "
+ "interrupt: %d:%02x\n", bank, v & int_mask);
+ }
+ v &= ~int_mask;
+ while (v) {
+ m = v & -v;
+ j = fls(m) - 1;
+ /*printk(KERN_INFO "msm_gpio_irq_handler %d:%02x %02x b"
+ "it %d irq %d\n", bank, v, m, j, int_base + j);*/
+ v &= ~m;
+ generic_handle_irq(int_base + j);
+ }
+ int_base += DREAM_INT_BANK0_COUNT;
+ }
+ desc->chip->ack(irq);
+}
+
+static int dream_sysdev_suspend(struct sys_device *dev, pm_message_t state)
+{
+ dream_suspended = 1;
+ writeb(dream_sleep_int_mask[0],
+ DREAM_CPLD_BASE + DREAM_GPIO_INT_MASK0_REG);
+ writeb(dream_sleep_int_mask[1],
+ DREAM_CPLD_BASE + DREAM_GPIO_INT_MASK1_REG);
+ writeb(dream_sleep_int_mask[0],
+ DREAM_CPLD_BASE + DREAM_GPIO_INT_STAT0_REG);
+ writeb(dream_sleep_int_mask[1],
+ DREAM_CPLD_BASE + DREAM_GPIO_INT_STAT1_REG);
+ return 0;
+}
+
+int dream_sysdev_resume(struct sys_device *dev)
+{
+ writeb(dream_int_mask[0], DREAM_CPLD_BASE + DREAM_GPIO_INT_MASK0_REG);
+ writeb(dream_int_mask[1], DREAM_CPLD_BASE + DREAM_GPIO_INT_MASK1_REG);
+ dream_suspended = 0;
+ return 0;
+}
+
+static struct irq_chip dream_gpio_irq_chip = {
+ .name = "dreamgpio",
+ .ack = dream_gpio_irq_ack,
+ .mask = dream_gpio_irq_mask,
+ .unmask = dream_gpio_irq_unmask,
+ .set_wake = dream_gpio_irq_set_wake,
+ //.set_type = dream_gpio_irq_set_type,
+};
+
+static struct gpio_chip dream_gpio_chip = {
+ .start = DREAM_GPIO_START,
+ .end = DREAM_GPIO_END,
+ .configure = dream_gpio_configure,
+ .get_irq_num = dream_gpio_get_irq_num,
+ .read = dream_gpio_read,
+ .write = dream_gpio_write,
+// .read_detect_status = dream_gpio_read_detect_status,
+// .clear_detect_status = dream_gpio_clear_detect_status
+};
+
+struct sysdev_class dream_sysdev_class = {
+ .name = "dreamgpio_irq",
+ .suspend = dream_sysdev_suspend,
+ .resume = dream_sysdev_resume,
+};
+
+static struct sys_device dream_irq_device = {
+ .cls = &dream_sysdev_class,
+};
+
+static int __init dream_init_gpio(void)
+{
+ int i;
+
+ if (!machine_is_trout())
+ return 0;
+
+ /* adjust GPIOs based on bootloader request */
+ pr_info("dream_init_gpio: cpld_usb_hw2_sw = %d\n", cpld_usb_h2w_sw);
+ dream_gpio_write_shadow(DREAM_GPIO_USB_H2W_SW, cpld_usb_h2w_sw);
+
+ for(i = 0; i < ARRAY_SIZE(dream_cpld_shadow); i++)
+ writeb(dream_cpld_shadow[i], DREAM_CPLD_BASE + i * 2);
+
+ for(i = DREAM_INT_START; i <= DREAM_INT_END; i++) {
+ set_irq_chip(i, &dream_gpio_irq_chip);
+ set_irq_handler(i, handle_edge_irq);
+ set_irq_flags(i, IRQF_VALID);
+ }
+
+ register_gpio_chip(&dream_gpio_chip);
+
+ set_irq_type(MSM_GPIO_TO_INT(17), IRQF_TRIGGER_HIGH);
+ set_irq_chained_handler(MSM_GPIO_TO_INT(17), dream_gpio_irq_handler);
+ set_irq_wake(MSM_GPIO_TO_INT(17), 1);
+
+ if(sysdev_class_register(&dream_sysdev_class) == 0)
+ sysdev_register(&dream_irq_device);
+
+ return 0;
+}
+
+postcore_initcall(dream_init_gpio);
diff --git a/arch/arm/mach-msm/board-dream.c b/arch/arm/mach-msm/board-dream.c
index d238e2c..4758957 100644
--- a/arch/arm/mach-msm/board-dream.c
+++ b/arch/arm/mach-msm/board-dream.c
@@ -18,11 +18,13 @@
#include <linux/kernel.h>
#include <linux/init.h>
#include <linux/platform_device.h>
+#include <linux/delay.h>

#include <asm/mach-types.h>
#include <asm/mach/arch.h>
#include <asm/mach/map.h>
#include <asm/setup.h>
+#include <asm/gpio.h>

#include <mach/board.h>
#include <mach/hardware.h>
@@ -62,9 +64,9 @@ static void __init dream_init(void)

static struct map_desc dream_io_desc[] __initdata = {
{
- .virtual = TROUT_CPLD_BASE,
- .pfn = __phys_to_pfn(TROUT_CPLD_START),
- .length = TROUT_CPLD_SIZE,
+ .virtual = DREAM_CPLD_BASE,
+ .pfn = __phys_to_pfn(DREAM_CPLD_START),
+ .length = DREAM_CPLD_SIZE,
.type = MT_DEVICE_NONSHARED
}
};
@@ -76,7 +78,7 @@ static void __init dream_map_io(void)

#ifdef CONFIG_MSM_DEBUG_UART3
/* route UART3 to the "H2W" extended usb connector */
- writeb(0x80, TROUT_CPLD_BASE + 0x00);
+ writeb(0x80, DREAM_CPLD_BASE + 0x00);
#endif

msm_clock_init();
diff --git a/arch/arm/mach-msm/board-dream.h b/arch/arm/mach-msm/board-dream.h
index 4f345a5..eadfd17 100644
--- a/arch/arm/mach-msm/board-dream.h
+++ b/arch/arm/mach-msm/board-dream.h
@@ -1,5 +1,153 @@

-#define TROUT_CPLD_BASE 0xE8100000
-#define TROUT_CPLD_START 0x98000000
-#define TROUT_CPLD_SIZE SZ_4K
+#define MSM_SMI_BASE 0x00000000
+#define MSM_SMI_SIZE 0x00800000

+#define MSM_EBI_BASE 0x10000000
+#define MSM_EBI_SIZE 0x06e00000
+
+#define MSM_PMEM_GPU0_BASE 0x00000000
+#define MSM_PMEM_GPU0_SIZE 0x00700000
+
+#define MSM_PMEM_MDP_BASE 0x02000000
+#define MSM_PMEM_MDP_SIZE 0x00800000
+
+#define MSM_PMEM_ADSP_BASE 0x02800000
+#define MSM_PMEM_ADSP_SIZE 0x00800000
+
+#define MSM_PMEM_CAMERA_BASE 0x03000000
+#define MSM_PMEM_CAMERA_SIZE 0x00800000
+
+#define MSM_FB_BASE 0x03800000
+#define MSM_FB_SIZE 0x00100000
+
+#define MSM_LINUX_BASE MSM_EBI_BASE
+#define MSM_LINUX_SIZE 0x06500000
+
+#define MSM_PMEM_GPU1_SIZE 0x800000
+#define MSM_PMEM_GPU1_BASE MSM_RAM_CONSOLE_BASE - MSM_PMEM_GPU1_SIZE
+
+#define MSM_RAM_CONSOLE_BASE MSM_EBI_BASE + 0x6d00000
+#define MSM_RAM_CONSOLE_SIZE 128 * SZ_1K
+
+#if (MSM_FB_BASE + MSM_FB_SIZE) >= (MSM_PMEM_GPU1_BASE)
+#error invalid memory map
+#endif
+
+#define DECLARE_MSM_IOMAP
+#include <mach/msm_iomap.h>
+
+#define DREAM_4_BALL_UP_0 1
+#define DREAM_4_BALL_LEFT_0 18
+#define DREAM_4_BALL_DOWN_0 57
+#define DREAM_4_BALL_RIGHT_0 91
+
+#define DREAM_5_BALL_UP_0 94
+#define DREAM_5_BALL_LEFT_0 18
+#define DREAM_5_BALL_DOWN_0 90
+#define DREAM_5_BALL_RIGHT_0 19
+
+#define DREAM_POWER_KEY 20
+
+#define DREAM_4_TP_LS_EN 19
+#define DREAM_5_TP_LS_EN 1
+
+#define DREAM_CPLD_BASE 0xE8100000
+#define DREAM_CPLD_START 0x98000000
+#define DREAM_CPLD_SIZE SZ_4K
+
+#define DREAM_GPIO_CABLE_IN1 (83)
+#define DREAM_GPIO_CABLE_IN2 (49)
+
+#define DREAM_GPIO_START (128)
+
+#define DREAM_GPIO_INT_MASK0_REG (0x0c)
+#define DREAM_GPIO_INT_STAT0_REG (0x0e)
+#define DREAM_GPIO_INT_MASK1_REG (0x14)
+#define DREAM_GPIO_INT_STAT1_REG (0x10)
+
+#define DREAM_GPIO_HAPTIC_PWM (28)
+#define DREAM_GPIO_PS_HOLD (25)
+
+#define DREAM_GPIO_MISC2_BASE (DREAM_GPIO_START + 0x00)
+#define DREAM_GPIO_MISC3_BASE (DREAM_GPIO_START + 0x08)
+#define DREAM_GPIO_MISC4_BASE (DREAM_GPIO_START + 0x10)
+#define DREAM_GPIO_MISC5_BASE (DREAM_GPIO_START + 0x18)
+#define DREAM_GPIO_INT2_BASE (DREAM_GPIO_START + 0x20)
+#define DREAM_GPIO_MISC1_BASE (DREAM_GPIO_START + 0x28)
+#define DREAM_GPIO_VIRTUAL_BASE (DREAM_GPIO_START + 0x30)
+#define DREAM_GPIO_INT5_BASE (DREAM_GPIO_START + 0x48)
+
+#define DREAM_GPIO_CHARGER_EN (DREAM_GPIO_MISC2_BASE + 0)
+#define DREAM_GPIO_ISET (DREAM_GPIO_MISC2_BASE + 1)
+#define DREAM_GPIO_H2W_DAT_DIR (DREAM_GPIO_MISC2_BASE + 2)
+#define DREAM_GPIO_H2W_CLK_DIR (DREAM_GPIO_MISC2_BASE + 3)
+#define DREAM_GPIO_H2W_DAT_GPO (DREAM_GPIO_MISC2_BASE + 4)
+#define DREAM_GPIO_H2W_CLK_GPO (DREAM_GPIO_MISC2_BASE + 5)
+#define DREAM_GPIO_H2W_SEL0 (DREAM_GPIO_MISC2_BASE + 6)
+#define DREAM_GPIO_H2W_SEL1 (DREAM_GPIO_MISC2_BASE + 7)
+
+#define DREAM_GPIO_SPOTLIGHT_EN (DREAM_GPIO_MISC3_BASE + 0)
+#define DREAM_GPIO_FLASH_EN (DREAM_GPIO_MISC3_BASE + 1)
+#define DREAM_GPIO_I2C_PULL (DREAM_GPIO_MISC3_BASE + 2)
+#define DREAM_GPIO_TP_I2C_PULL (DREAM_GPIO_MISC3_BASE + 3)
+#define DREAM_GPIO_TP_EN (DREAM_GPIO_MISC3_BASE + 4)
+#define DREAM_GPIO_JOG_EN (DREAM_GPIO_MISC3_BASE + 5)
+#define DREAM_GPIO_UI_LED_EN (DREAM_GPIO_MISC3_BASE + 6)
+#define DREAM_GPIO_QTKEY_LED_EN (DREAM_GPIO_MISC3_BASE + 7)
+
+#define DREAM_GPIO_VCM_PWDN (DREAM_GPIO_MISC4_BASE + 0)
+#define DREAM_GPIO_USB_H2W_SW (DREAM_GPIO_MISC4_BASE + 1)
+#define DREAM_GPIO_COMPASS_RST_N (DREAM_GPIO_MISC4_BASE + 2)
+#define DREAM_GPIO_HAPTIC_EN_UP (DREAM_GPIO_MISC4_BASE + 3)
+#define DREAM_GPIO_HAPTIC_EN_MAIN (DREAM_GPIO_MISC4_BASE + 4)
+#define DREAM_GPIO_USB_PHY_RST_N (DREAM_GPIO_MISC4_BASE + 5)
+#define DREAM_GPIO_WIFI_PA_RESETX (DREAM_GPIO_MISC4_BASE + 6)
+#define DREAM_GPIO_WIFI_EN (DREAM_GPIO_MISC4_BASE + 7)
+
+#define DREAM_GPIO_BT_32K_EN (DREAM_GPIO_MISC5_BASE + 0)
+#define DREAM_GPIO_MAC_32K_EN (DREAM_GPIO_MISC5_BASE + 1)
+#define DREAM_GPIO_MDDI_32K_EN (DREAM_GPIO_MISC5_BASE + 2)
+#define DREAM_GPIO_COMPASS_32K_EN (DREAM_GPIO_MISC5_BASE + 3)
+
+#define DREAM_GPIO_NAVI_ACT_N (DREAM_GPIO_INT2_BASE + 0)
+#define DREAM_GPIO_COMPASS_IRQ (DREAM_GPIO_INT2_BASE + 1)
+#define DREAM_GPIO_SLIDING_DET (DREAM_GPIO_INT2_BASE + 2)
+#define DREAM_GPIO_AUD_HSMIC_DET_N (DREAM_GPIO_INT2_BASE + 3)
+#define DREAM_GPIO_SD_DOOR_N (DREAM_GPIO_INT2_BASE + 4)
+#define DREAM_GPIO_CAM_BTN_STEP1_N (DREAM_GPIO_INT2_BASE + 5)
+#define DREAM_GPIO_CAM_BTN_STEP2_N (DREAM_GPIO_INT2_BASE + 6)
+#define DREAM_GPIO_TP_ATT_N (DREAM_GPIO_INT2_BASE + 7)
+#define DREAM_GPIO_BANK0_FIRST_INT_SOURCE (DREAM_GPIO_NAVI_ACT_N)
+#define DREAM_GPIO_BANK0_LAST_INT_SOURCE (DREAM_GPIO_TP_ATT_N)
+
+#define DREAM_GPIO_H2W_DAT_GPI (DREAM_GPIO_MISC1_BASE + 0)
+#define DREAM_GPIO_H2W_CLK_GPI (DREAM_GPIO_MISC1_BASE + 1)
+#define DREAM_GPIO_CPLD128_VER_0 (DREAM_GPIO_MISC1_BASE + 4)
+#define DREAM_GPIO_CPLD128_VER_1 (DREAM_GPIO_MISC1_BASE + 5)
+#define DREAM_GPIO_CPLD128_VER_2 (DREAM_GPIO_MISC1_BASE + 6)
+#define DREAM_GPIO_CPLD128_VER_3 (DREAM_GPIO_MISC1_BASE + 7)
+
+#define DREAM_GPIO_SDMC_CD_N (DREAM_GPIO_VIRTUAL_BASE + 0)
+#define DREAM_GPIO_END (DREAM_GPIO_SDMC_CD_N)
+#define DREAM_GPIO_BANK1_FIRST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
+#define DREAM_GPIO_BANK1_LAST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
+
+#define DREAM_GPIO_VIRTUAL_TO_REAL_OFFSET \
+ (DREAM_GPIO_INT5_BASE - DREAM_GPIO_VIRTUAL_BASE)
+
+#define DREAM_INT_START (NR_MSM_IRQS + NR_GPIO_IRQS)
+#define DREAM_INT_BANK0_COUNT (8)
+#define DREAM_INT_BANK1_START (DREAM_INT_START + DREAM_INT_BANK0_COUNT)
+#define DREAM_INT_BANK1_COUNT (1)
+#define DREAM_INT_END (DREAM_INT_START + DREAM_INT_BANK0_COUNT + \
+ DREAM_INT_BANK1_COUNT - 1)
+#define DREAM_GPIO_TO_INT(n) (((n) <= DREAM_GPIO_BANK0_LAST_INT_SOURCE) ? \
+ (DREAM_INT_START - DREAM_GPIO_BANK0_FIRST_INT_SOURCE + (n)) : \
+ (DREAM_INT_BANK1_START - DREAM_GPIO_BANK1_FIRST_INT_SOURCE + (n)))
+
+#define DREAM_INT_TO_BANK(n) ((n - DREAM_INT_START) / DREAM_INT_BANK0_COUNT)
+#define DREAM_INT_TO_MASK(n) (1U << ((n - DREAM_INT_START) & 7))
+#define DREAM_BANK_TO_MASK_REG(bank) \
+ (bank ? DREAM_GPIO_INT_MASK1_REG : DREAM_GPIO_INT_MASK0_REG)
+#define DREAM_BANK_TO_STAT_REG(bank) \
+ (bank ? DREAM_GPIO_INT_STAT1_REG : DREAM_GPIO_INT_STAT0_REG)
diff --git a/arch/arm/mach-msm/generic_gpio.c b/arch/arm/mach-msm/generic_gpio.c
new file mode 100644
index 0000000..fe24d38
--- /dev/null
+++ b/arch/arm/mach-msm/generic_gpio.c
@@ -0,0 +1,274 @@
+/* arch/arm/mach-msm/generic_gpio.c
+ *
+ * Copyright (C) 2007 Google, Inc.
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that 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/kernel.h>
+#include <linux/module.h>
+#include <linux/errno.h>
+#include <linux/slab.h>
+#include <linux/spinlock.h>
+#include <asm/gpio.h>
+#include "gpio_chip.h"
+
+#define GPIO_NUM_TO_CHIP_INDEX(gpio) ((gpio)>>5)
+
+struct gpio_state {
+ unsigned long flags;
+ int refcount;
+};
+
+static DEFINE_SPINLOCK(gpio_chips_lock);
+static LIST_HEAD(gpio_chip_list);
+static struct gpio_chip **gpio_chip_array;
+static unsigned long gpio_chip_array_size;
+
+int register_gpio_chip(struct gpio_chip *new_gpio_chip)
+{
+ int err = 0;
+ struct gpio_chip *gpio_chip;
+ int i;
+ unsigned long irq_flags;
+ unsigned int chip_array_start_index, chip_array_end_index;
+
+ new_gpio_chip->state = kzalloc((new_gpio_chip->end + 1 - new_gpio_chip->start) * sizeof(new_gpio_chip->state[0]), GFP_KERNEL);
+ if (new_gpio_chip->state == NULL) {
+ printk(KERN_ERR "register_gpio_chip: failed to allocate state\n");
+ return -ENOMEM;
+ }
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip_array_start_index = GPIO_NUM_TO_CHIP_INDEX(new_gpio_chip->start);
+ chip_array_end_index = GPIO_NUM_TO_CHIP_INDEX(new_gpio_chip->end);
+ if (chip_array_end_index >= gpio_chip_array_size) {
+ struct gpio_chip **new_gpio_chip_array;
+ unsigned long new_gpio_chip_array_size = chip_array_end_index + 1;
+
+ new_gpio_chip_array = kmalloc(new_gpio_chip_array_size * sizeof(new_gpio_chip_array[0]), GFP_ATOMIC);
+ if (new_gpio_chip_array == NULL) {
+ printk(KERN_ERR "register_gpio_chip: failed to allocate array\n");
+ err = -ENOMEM;
+ goto failed;
+ }
+ for (i = 0; i < gpio_chip_array_size; i++)
+ new_gpio_chip_array[i] = gpio_chip_array[i];
+ for (i = gpio_chip_array_size; i < new_gpio_chip_array_size; i++)
+ new_gpio_chip_array[i] = NULL;
+ gpio_chip_array = new_gpio_chip_array;
+ gpio_chip_array_size = new_gpio_chip_array_size;
+ }
+ list_for_each_entry(gpio_chip, &gpio_chip_list, list) {
+ if (gpio_chip->start > new_gpio_chip->end) {
+ list_add_tail(&new_gpio_chip->list, &gpio_chip->list);
+ goto added;
+ }
+ if (gpio_chip->end >= new_gpio_chip->start) {
+ printk(KERN_ERR "register_gpio_source %u-%u overlaps with %u-%u\n",
+ new_gpio_chip->start, new_gpio_chip->end,
+ gpio_chip->start, gpio_chip->end);
+ err = -EBUSY;
+ goto failed;
+ }
+ }
+ list_add_tail(&new_gpio_chip->list, &gpio_chip_list);
+added:
+ for (i = chip_array_start_index; i <= chip_array_end_index; i++) {
+ if (gpio_chip_array[i] == NULL || gpio_chip_array[i]->start > new_gpio_chip->start)
+ gpio_chip_array[i] = new_gpio_chip;
+ }
+failed:
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ if (err)
+ kfree(new_gpio_chip->state);
+ return err;
+}
+
+static struct gpio_chip *get_gpio_chip_locked(unsigned int gpio)
+{
+ unsigned long i;
+ struct gpio_chip *chip;
+
+ i = GPIO_NUM_TO_CHIP_INDEX(gpio);
+ if (i >= gpio_chip_array_size)
+ return NULL;
+ chip = gpio_chip_array[i];
+ if (chip == NULL)
+ return NULL;
+ list_for_each_entry_from(chip, &gpio_chip_list, list) {
+ if (gpio < chip->start)
+ return NULL;
+ if (gpio <= chip->end)
+ return chip;
+ }
+ return NULL;
+}
+
+static int request_gpio(unsigned int gpio, unsigned long flags)
+{
+ int err = 0;
+ struct gpio_chip *chip;
+ unsigned long irq_flags;
+ unsigned long chip_index;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip == NULL) {
+ err = -EINVAL;
+ goto err;
+ }
+ chip_index = gpio - chip->start;
+ if (chip->state[chip_index].refcount == 0) {
+ chip->configure(chip, gpio, flags);
+ chip->state[chip_index].flags = flags;
+ chip->state[chip_index].refcount++;
+ } else if ((flags & IRQF_SHARED) && (chip->state[chip_index].flags & IRQF_SHARED))
+ chip->state[chip_index].refcount++;
+ else
+ err = -EBUSY;
+err:
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ return err;
+}
+
+int gpio_request(unsigned gpio, const char *label)
+{
+ return request_gpio(gpio, 0);
+}
+EXPORT_SYMBOL(gpio_request);
+
+void gpio_free(unsigned gpio)
+{
+ struct gpio_chip *chip;
+ unsigned long irq_flags;
+ unsigned long chip_index;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip) {
+ chip_index = gpio - chip->start;
+ chip->state[chip_index].refcount--;
+ }
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+}
+EXPORT_SYMBOL(gpio_free);
+
+static int gpio_get_irq_num(unsigned int gpio, unsigned int *irqp, unsigned long *irqnumflagsp)
+{
+ int ret = -ENOTSUPP;
+ struct gpio_chip *chip;
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip && chip->get_irq_num)
+ ret = chip->get_irq_num(chip, gpio, irqp, irqnumflagsp);
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ return ret;
+}
+
+int gpio_to_irq(unsigned gpio)
+{
+ int ret, irq;
+ ret = gpio_get_irq_num(gpio, &irq, NULL);
+ if (ret)
+ return ret;
+ return irq;
+}
+EXPORT_SYMBOL(gpio_to_irq);
+
+int gpio_configure(unsigned int gpio, unsigned long flags)
+{
+ int ret = -ENOTSUPP;
+ struct gpio_chip *chip;
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip)
+ ret = chip->configure(chip, gpio, flags);
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ return ret;
+}
+EXPORT_SYMBOL(gpio_configure);
+
+int gpio_direction_input(unsigned gpio)
+{
+ return gpio_configure(gpio, GPIOF_INPUT);
+}
+EXPORT_SYMBOL(gpio_direction_input);
+
+int gpio_direction_output(unsigned gpio, int value)
+{
+ gpio_set_value(gpio, value);
+ return gpio_configure(gpio, GPIOF_DRIVE_OUTPUT);
+}
+EXPORT_SYMBOL(gpio_direction_output);
+
+int gpio_get_value(unsigned gpio)
+{
+ int ret = -ENOTSUPP;
+ struct gpio_chip *chip;
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip && chip->read)
+ ret = chip->read(chip, gpio);
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ return ret;
+}
+EXPORT_SYMBOL(gpio_get_value);
+
+void gpio_set_value(unsigned gpio, int on)
+{
+ int ret = -ENOTSUPP;
+ struct gpio_chip *chip;
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip && chip->write)
+ ret = chip->write(chip, gpio, on);
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+}
+EXPORT_SYMBOL(gpio_set_value);
+
+int gpio_read_detect_status(unsigned int gpio)
+{
+ int ret = -ENOTSUPP;
+ struct gpio_chip *chip;
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip && chip->read_detect_status)
+ ret = chip->read_detect_status(chip, gpio);
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ return ret;
+}
+EXPORT_SYMBOL(gpio_read_detect_status);
+
+int gpio_clear_detect_status(unsigned int gpio)
+{
+ int ret = -ENOTSUPP;
+ struct gpio_chip *chip;
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip && chip->clear_detect_status)
+ ret = chip->clear_detect_status(chip, gpio);
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ return ret;
+}
+EXPORT_SYMBOL(gpio_clear_detect_status);
diff --git a/arch/arm/mach-msm/gpio_chip.h b/arch/arm/mach-msm/gpio_chip.h
new file mode 100644
index 0000000..ee4eddc
--- /dev/null
+++ b/arch/arm/mach-msm/gpio_chip.h
@@ -0,0 +1,50 @@
+/* arch/arm/mach-msm/gpio_chip.h
+ *
+ * Copyright (C) 2007 Google, Inc.
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that 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.
+ *
+ */
+
+#ifndef _LINUX_GPIO_CHIP_H
+#define _LINUX_GPIO_CHIP_H
+
+#include <linux/list.h>
+
+struct gpio_chip {
+ struct list_head list;
+ struct gpio_state *state;
+
+ unsigned int start;
+ unsigned int end;
+
+ int (*configure)(struct gpio_chip *chip, unsigned int gpio, unsigned long flags);
+ int (*get_irq_num)(struct gpio_chip *chip, unsigned int gpio, unsigned int *irqp, unsigned long *irqnumflagsp);
+ int (*read)(struct gpio_chip *chip, unsigned int gpio);
+ int (*write)(struct gpio_chip *chip, unsigned int gpio, unsigned on);
+ int (*read_detect_status)(struct gpio_chip *chip, unsigned int gpio);
+ int (*clear_detect_status)(struct gpio_chip *chip, unsigned int gpio);
+};
+
+int register_gpio_chip(struct gpio_chip *gpio_chip);
+
+/* extended gpio api */
+
+#define GPIOF_IRQF_MASK 0x0000ffff /* use to specify edge detection without */
+#define GPIOF_IRQF_TRIGGER_NONE 0x00010000 /* IRQF_TRIGGER_NONE is 0 which also means "as already configured" */
+#define GPIOF_INPUT 0x00020000
+#define GPIOF_DRIVE_OUTPUT 0x00040000
+#define GPIOF_OUTPUT_LOW 0x00080000
+#define GPIOF_OUTPUT_HIGH 0x00100000
+
+#define GPIOIRQF_SHARED 0x00000001 /* the irq line is shared with other inputs */
+
+
+#endif
diff --git a/arch/arm/mach-msm/include/mach/gpio.h b/arch/arm/mach-msm/include/mach/gpio.h
new file mode 100644
index 0000000..92ce18d
--- /dev/null
+++ b/arch/arm/mach-msm/include/mach/gpio.h
@@ -0,0 +1,36 @@
+/* linux/include/asm-arm/arch-msm/gpio.h
+ *
+ * Copyright (C) 2007 Google, Inc.
+ * Author: Mike Lockwood <[email protected]>
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that 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.
+ *
+ */
+
+#ifndef __ASM_ARCH_MSM_GPIO_H
+#define __ASM_ARCH_MSM_GPIO_H
+
+#include <linux/interrupt.h>
+
+int gpio_request(unsigned gpio, const char *label);
+void gpio_free(unsigned gpio);
+int gpio_direction_input(unsigned gpio);
+int gpio_direction_output(unsigned gpio, int value);
+int gpio_get_value(unsigned gpio);
+void gpio_set_value(unsigned gpio, int value);
+int gpio_to_irq(unsigned gpio);
+
+#include <asm-generic/gpio.h>
+
+extern int gpio_configure(unsigned int gpio, unsigned long flags);
+extern int gpio_read_detect_status(unsigned int gpio);
+extern int gpio_clear_detect_status(unsigned int gpio);
+
+#endif


--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html


2009-12-08 20:21:52

by Ryan Mallon

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

Pavel Machek wrote:
> Add GPIO support for HTC Dream.
>
> Signed-off-by: Pavel Machek <[email protected]>

You might want to run this through checkpatch, I suspect it is going to
give you several errors. Some other comments inline.

> diff --git a/arch/arm/mach-msm/Kconfig b/arch/arm/mach-msm/Kconfig
> index f780086..774c50e 100644
> --- a/arch/arm/mach-msm/Kconfig
> +++ b/arch/arm/mach-msm/Kconfig
> @@ -40,4 +40,8 @@ config MACH_TROUT
> help
> Support for the HTC Dream, T-Mobile G1, Android ADP1 devices.
>
> +config GENERIC_GPIO
> + bool
> + default y
> +
> endif
> diff --git a/arch/arm/mach-msm/Makefile b/arch/arm/mach-msm/Makefile
> index 91e6f5c..4c2567e 100644
> --- a/arch/arm/mach-msm/Makefile
> +++ b/arch/arm/mach-msm/Makefile
> @@ -6,4 +6,4 @@ obj-y += clock.o clock-7x01a.o
>
> obj-$(CONFIG_MACH_HALIBUT) += board-halibut.o
>
> -obj-$(CONFIG_MACH_TROUT) += board-dream.o
> +obj-$(CONFIG_MACH_TROUT) += board-dream.o board-dream-gpio.o generic_gpio.o
> diff --git a/arch/arm/mach-msm/board-dream-gpio.c b/arch/arm/mach-msm/board-dream-gpio.c
> new file mode 100644
> index 0000000..1b23a84
> --- /dev/null
> +++ b/arch/arm/mach-msm/board-dream-gpio.c
> @@ -0,0 +1,301 @@
> +/* arch/arm/mach-msm/board-dream-gpio.c
> + *
> + * Copyright (C) 2008 Google, Inc.
> + *
> + * This software is licensed under the terms of the GNU General Public
> + * License version 2, as published by the Free Software Foundation, and
> + * may be copied, distributed, and modified under those terms.
> + *
> + * This program is distributed in the hope that 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/kernel.h>
> +#include <linux/errno.h>
> +#include <linux/irq.h>
> +#include <linux/pm.h>
> +#include <linux/sysdev.h>
> +#include <linux/io.h>
> +
> +#include <asm/gpio.h>
> +#include <asm/mach-types.h>
> +
> +#include "board-dream.h"
> +#include "gpio_chip.h"
> +
> +#undef MODULE_PARAM_PREFIX
> +#define MODULE_PARAM_PREFIX "board_dream."

This looks a bit dodgy. Is this
(http://lkml.indiana.edu/hypermail/linux/kernel/0903.0/02768.html) the
preferred way?

> +static uint cpld_usb_h2w_sw;
> +module_param_named(usb_h2w_sw, cpld_usb_h2w_sw, uint, 0);
> +
> +static uint8_t dream_cpld_shadow[4] = {
> +#if defined(CONFIG_MSM_DEBUG_UART1)
> + /* H2W pins <-> UART1 */
> + [0] = 0x40, // for serial debug, low current
> +#else
> + /* H2W pins <-> UART3, Bluetooth <-> UART1 */
> + [0] = 0x80, // for serial debug, low current
> +#endif
> + [1] = 0x04, // I2C_PULL
> + [3] = 0x04, // mmdi 32k en
> +};
> +static uint8_t dream_int_mask[2] = {
> + [0] = 0xff, /* mask all interrupts */
> + [1] = 0xff,
> +};
> +static uint8_t dream_sleep_int_mask[] = {
> + [0] = 0xff,
> + [1] = 0xff,
> +};
> +static int dream_suspended;
> +
> +static int dream_gpio_read(struct gpio_chip *chip, unsigned n)
> +{
> + uint8_t b;
> + int reg;
> + if (n >= DREAM_GPIO_VIRTUAL_BASE)
> + n += DREAM_GPIO_VIRTUAL_TO_REAL_OFFSET;
> + b = 1U << (n & 7);
> + reg = (n & 0x78) >> 2; // assumes base is 128
> + return !!(readb(DREAM_CPLD_BASE + reg) & b);
> +}
> +
> +static void update_pwrsink(unsigned gpio, unsigned on)
> +{
> + switch(gpio) {
> + case DREAM_GPIO_UI_LED_EN:
> + break;
> + case DREAM_GPIO_QTKEY_LED_EN:
> + break;
> + }
> +}

What is this function for?

> +static uint8_t dream_gpio_write_shadow(unsigned n, unsigned on)
> +{
> + uint8_t b = 1U << (n & 7);
> + int reg = (n & 0x78) >> 2; // assumes base is 128
> +
> + if(on)
> + return dream_cpld_shadow[reg >> 1] |= b;
> + else
> + return dream_cpld_shadow[reg >> 1] &= ~b;
> +}
> +
> +static int dream_gpio_write(struct gpio_chip *chip, unsigned n, unsigned on)
> +{
> + int reg = (n & 0x78) >> 2; // assumes base is 128
> + unsigned long flags;
> + uint8_t reg_val;
> +
> + if ((reg >> 1) >= ARRAY_SIZE(dream_cpld_shadow)) {
> + printk(KERN_ERR "dream_gpio_write called on input %d\n", n);
> + return -ENOTSUPP;
> + }
> +
> + local_irq_save(flags);
> + update_pwrsink(n, on);
> + reg_val = dream_gpio_write_shadow(n, on);
> + writeb(reg_val, DREAM_CPLD_BASE + reg);
> + local_irq_restore(flags);
> + return 0;
> +}
> +
> +static int dream_gpio_configure(struct gpio_chip *chip, unsigned int gpio, unsigned long flags)
> +{
> + if(flags & (GPIOF_OUTPUT_LOW | GPIOF_OUTPUT_HIGH))
> + dream_gpio_write(chip, gpio, flags & GPIOF_OUTPUT_HIGH);
> + return 0;
> +}
> +
> +static int dream_gpio_get_irq_num(struct gpio_chip *chip, unsigned int gpio, unsigned int *irqp, unsigned long *irqnumflagsp)
> +{
> + if ((gpio < DREAM_GPIO_BANK0_FIRST_INT_SOURCE ||
> + gpio > DREAM_GPIO_BANK0_LAST_INT_SOURCE) &&
> + (gpio < DREAM_GPIO_BANK1_FIRST_INT_SOURCE ||
> + gpio > DREAM_GPIO_BANK1_LAST_INT_SOURCE))
> + return -ENOENT;
> + *irqp = DREAM_GPIO_TO_INT(gpio);
> + if(irqnumflagsp)
> + *irqnumflagsp = 0;
> + return 0;
> +}
> +
> +static void dream_gpio_irq_ack(unsigned int irq)
> +{
> + int bank = DREAM_INT_TO_BANK(irq);
> + uint8_t mask = DREAM_INT_TO_MASK(irq);
> + int reg = DREAM_BANK_TO_STAT_REG(bank);
> + /*printk(KERN_INFO "dream_gpio_irq_ack irq %d\n", irq);*/

pr_debug, or just remove it?

> + writeb(mask, DREAM_CPLD_BASE + reg);
> +}
> +
> +static void dream_gpio_irq_mask(unsigned int irq)
> +{
> + unsigned long flags;
> + uint8_t reg_val;
> + int bank = DREAM_INT_TO_BANK(irq);
> + uint8_t mask = DREAM_INT_TO_MASK(irq);
> + int reg = DREAM_BANK_TO_MASK_REG(bank);
> +
> + local_irq_save(flags);
> + reg_val = dream_int_mask[bank] |= mask;
> + /*printk(KERN_INFO "dream_gpio_irq_mask irq %d => %d:%02x\n",
> + irq, bank, reg_val);*/
> + if (!dream_suspended)
> + writeb(reg_val, DREAM_CPLD_BASE + reg);
> + local_irq_restore(flags);
> +}
> +
> +static void dream_gpio_irq_unmask(unsigned int irq)
> +{
> + unsigned long flags;
> + uint8_t reg_val;
> + int bank = DREAM_INT_TO_BANK(irq);
> + uint8_t mask = DREAM_INT_TO_MASK(irq);
> + int reg = DREAM_BANK_TO_MASK_REG(bank);
> +
> + local_irq_save(flags);
> + reg_val = dream_int_mask[bank] &= ~mask;
> + /*printk(KERN_INFO "dream_gpio_irq_unmask irq %d => %d:%02x\n",
> + irq, bank, reg_val);*/
> + if (!dream_suspended)
> + writeb(reg_val, DREAM_CPLD_BASE + reg);
> + local_irq_restore(flags);
> +}
> +
> +int dream_gpio_irq_set_wake(unsigned int irq, unsigned int on)
> +{
> + unsigned long flags;
> + int bank = DREAM_INT_TO_BANK(irq);
> + uint8_t mask = DREAM_INT_TO_MASK(irq);
> +
> + local_irq_save(flags);
> + if(on)
> + dream_sleep_int_mask[bank] &= ~mask;
> + else
> + dream_sleep_int_mask[bank] |= mask;
> + local_irq_restore(flags);
> + return 0;
> +}
> +
> +static void dream_gpio_irq_handler(unsigned int irq, struct irq_desc *desc)
> +{
> + int j, m;
> + unsigned v;
> + int bank;
> + int stat_reg;
> + int int_base = DREAM_INT_START;
> + uint8_t int_mask;
> +
> + for (bank = 0; bank < 2; bank++) {
> + stat_reg = DREAM_BANK_TO_STAT_REG(bank);
> + v = readb(DREAM_CPLD_BASE + stat_reg);
> + int_mask = dream_int_mask[bank];
> + if (v & int_mask) {
> + writeb(v & int_mask, DREAM_CPLD_BASE + stat_reg);
> + printk(KERN_ERR "dream_gpio_irq_handler: got masked "
> + "interrupt: %d:%02x\n", bank, v & int_mask);
> + }
> + v &= ~int_mask;
> + while (v) {
> + m = v & -v;
> + j = fls(m) - 1;
> + /*printk(KERN_INFO "msm_gpio_irq_handler %d:%02x %02x b"
> + "it %d irq %d\n", bank, v, m, j, int_base + j);*/
> + v &= ~m;
> + generic_handle_irq(int_base + j);
> + }
> + int_base += DREAM_INT_BANK0_COUNT;
> + }
> + desc->chip->ack(irq);
> +}

Some blank lines here and there would make this more readable. All your
code is wedged together :-).

> +static int dream_sysdev_suspend(struct sys_device *dev, pm_message_t state)
> +{
> + dream_suspended = 1;
> + writeb(dream_sleep_int_mask[0],
> + DREAM_CPLD_BASE + DREAM_GPIO_INT_MASK0_REG);
> + writeb(dream_sleep_int_mask[1],
> + DREAM_CPLD_BASE + DREAM_GPIO_INT_MASK1_REG);
> + writeb(dream_sleep_int_mask[0],
> + DREAM_CPLD_BASE + DREAM_GPIO_INT_STAT0_REG);
> + writeb(dream_sleep_int_mask[1],
> + DREAM_CPLD_BASE + DREAM_GPIO_INT_STAT1_REG);
> + return 0;
> +}
> +
> +int dream_sysdev_resume(struct sys_device *dev)
> +{
> + writeb(dream_int_mask[0], DREAM_CPLD_BASE + DREAM_GPIO_INT_MASK0_REG);
> + writeb(dream_int_mask[1], DREAM_CPLD_BASE + DREAM_GPIO_INT_MASK1_REG);
> + dream_suspended = 0;
> + return 0;
> +}
> +
> +static struct irq_chip dream_gpio_irq_chip = {
> + .name = "dreamgpio",
> + .ack = dream_gpio_irq_ack,
> + .mask = dream_gpio_irq_mask,
> + .unmask = dream_gpio_irq_unmask,
> + .set_wake = dream_gpio_irq_set_wake,
> + //.set_type = dream_gpio_irq_set_type,
> +};
> +
> +static struct gpio_chip dream_gpio_chip = {
> + .start = DREAM_GPIO_START,
> + .end = DREAM_GPIO_END,
> + .configure = dream_gpio_configure,
> + .get_irq_num = dream_gpio_get_irq_num,
> + .read = dream_gpio_read,
> + .write = dream_gpio_write,
> +// .read_detect_status = dream_gpio_read_detect_status,
> +// .clear_detect_status = dream_gpio_clear_detect_status
> +};
> +
> +struct sysdev_class dream_sysdev_class = {
> + .name = "dreamgpio_irq",
> + .suspend = dream_sysdev_suspend,
> + .resume = dream_sysdev_resume,
> +};
> +
> +static struct sys_device dream_irq_device = {
> + .cls = &dream_sysdev_class,
> +};
> +
> +static int __init dream_init_gpio(void)
> +{
> + int i;
> +
> + if (!machine_is_trout())
> + return 0;
> +
> + /* adjust GPIOs based on bootloader request */
> + pr_info("dream_init_gpio: cpld_usb_hw2_sw = %d\n", cpld_usb_h2w_sw);
> + dream_gpio_write_shadow(DREAM_GPIO_USB_H2W_SW, cpld_usb_h2w_sw);
> +
> + for(i = 0; i < ARRAY_SIZE(dream_cpld_shadow); i++)
> + writeb(dream_cpld_shadow[i], DREAM_CPLD_BASE + i * 2);
> +
> + for(i = DREAM_INT_START; i <= DREAM_INT_END; i++) {
> + set_irq_chip(i, &dream_gpio_irq_chip);
> + set_irq_handler(i, handle_edge_irq);
> + set_irq_flags(i, IRQF_VALID);
> + }
> +
> + register_gpio_chip(&dream_gpio_chip);
> +
> + set_irq_type(MSM_GPIO_TO_INT(17), IRQF_TRIGGER_HIGH);
> + set_irq_chained_handler(MSM_GPIO_TO_INT(17), dream_gpio_irq_handler);
> + set_irq_wake(MSM_GPIO_TO_INT(17), 1);
> +
> + if(sysdev_class_register(&dream_sysdev_class) == 0)
> + sysdev_register(&dream_irq_device);
> +
> + return 0;
> +}
> +
> +postcore_initcall(dream_init_gpio);
> diff --git a/arch/arm/mach-msm/board-dream.c b/arch/arm/mach-msm/board-dream.c
> index d238e2c..4758957 100644
> --- a/arch/arm/mach-msm/board-dream.c
> +++ b/arch/arm/mach-msm/board-dream.c
> @@ -18,11 +18,13 @@
> #include <linux/kernel.h>
> #include <linux/init.h>
> #include <linux/platform_device.h>
> +#include <linux/delay.h>
>
> #include <asm/mach-types.h>
> #include <asm/mach/arch.h>
> #include <asm/mach/map.h>
> #include <asm/setup.h>
> +#include <asm/gpio.h>
>
> #include <mach/board.h>
> #include <mach/hardware.h>
> @@ -62,9 +64,9 @@ static void __init dream_init(void)
>
> static struct map_desc dream_io_desc[] __initdata = {
> {
> - .virtual = TROUT_CPLD_BASE,
> - .pfn = __phys_to_pfn(TROUT_CPLD_START),
> - .length = TROUT_CPLD_SIZE,
> + .virtual = DREAM_CPLD_BASE,
> + .pfn = __phys_to_pfn(DREAM_CPLD_START),
> + .length = DREAM_CPLD_SIZE,
> .type = MT_DEVICE_NONSHARED
> }
> };
> @@ -76,7 +78,7 @@ static void __init dream_map_io(void)
>
> #ifdef CONFIG_MSM_DEBUG_UART3
> /* route UART3 to the "H2W" extended usb connector */
> - writeb(0x80, TROUT_CPLD_BASE + 0x00);
> + writeb(0x80, DREAM_CPLD_BASE + 0x00);
> #endif
>
> msm_clock_init();
> diff --git a/arch/arm/mach-msm/board-dream.h b/arch/arm/mach-msm/board-dream.h
> index 4f345a5..eadfd17 100644
> --- a/arch/arm/mach-msm/board-dream.h
> +++ b/arch/arm/mach-msm/board-dream.h
> @@ -1,5 +1,153 @@
>
> -#define TROUT_CPLD_BASE 0xE8100000
> -#define TROUT_CPLD_START 0x98000000
> -#define TROUT_CPLD_SIZE SZ_4K
> +#define MSM_SMI_BASE 0x00000000
> +#define MSM_SMI_SIZE 0x00800000
>
> +#define MSM_EBI_BASE 0x10000000
> +#define MSM_EBI_SIZE 0x06e00000
> +
> +#define MSM_PMEM_GPU0_BASE 0x00000000
> +#define MSM_PMEM_GPU0_SIZE 0x00700000
> +
> +#define MSM_PMEM_MDP_BASE 0x02000000
> +#define MSM_PMEM_MDP_SIZE 0x00800000
> +
> +#define MSM_PMEM_ADSP_BASE 0x02800000
> +#define MSM_PMEM_ADSP_SIZE 0x00800000
> +
> +#define MSM_PMEM_CAMERA_BASE 0x03000000
> +#define MSM_PMEM_CAMERA_SIZE 0x00800000
> +
> +#define MSM_FB_BASE 0x03800000
> +#define MSM_FB_SIZE 0x00100000
> +
> +#define MSM_LINUX_BASE MSM_EBI_BASE
> +#define MSM_LINUX_SIZE 0x06500000
> +
> +#define MSM_PMEM_GPU1_SIZE 0x800000
> +#define MSM_PMEM_GPU1_BASE MSM_RAM_CONSOLE_BASE - MSM_PMEM_GPU1_SIZE
> +
> +#define MSM_RAM_CONSOLE_BASE MSM_EBI_BASE + 0x6d00000
> +#define MSM_RAM_CONSOLE_SIZE 128 * SZ_1K
> +
> +#if (MSM_FB_BASE + MSM_FB_SIZE) >= (MSM_PMEM_GPU1_BASE)
> +#error invalid memory map
> +#endif
> +
> +#define DECLARE_MSM_IOMAP
> +#include <mach/msm_iomap.h>
> +
> +#define DREAM_4_BALL_UP_0 1
> +#define DREAM_4_BALL_LEFT_0 18
> +#define DREAM_4_BALL_DOWN_0 57
> +#define DREAM_4_BALL_RIGHT_0 91
> +
> +#define DREAM_5_BALL_UP_0 94
> +#define DREAM_5_BALL_LEFT_0 18
> +#define DREAM_5_BALL_DOWN_0 90
> +#define DREAM_5_BALL_RIGHT_0 19
> +
> +#define DREAM_POWER_KEY 20
> +
> +#define DREAM_4_TP_LS_EN 19
> +#define DREAM_5_TP_LS_EN 1
> +
> +#define DREAM_CPLD_BASE 0xE8100000
> +#define DREAM_CPLD_START 0x98000000
> +#define DREAM_CPLD_SIZE SZ_4K
> +
> +#define DREAM_GPIO_CABLE_IN1 (83)
> +#define DREAM_GPIO_CABLE_IN2 (49)
> +
> +#define DREAM_GPIO_START (128)
> +
> +#define DREAM_GPIO_INT_MASK0_REG (0x0c)
> +#define DREAM_GPIO_INT_STAT0_REG (0x0e)
> +#define DREAM_GPIO_INT_MASK1_REG (0x14)
> +#define DREAM_GPIO_INT_STAT1_REG (0x10)
> +
> +#define DREAM_GPIO_HAPTIC_PWM (28)
> +#define DREAM_GPIO_PS_HOLD (25)
> +
> +#define DREAM_GPIO_MISC2_BASE (DREAM_GPIO_START + 0x00)
> +#define DREAM_GPIO_MISC3_BASE (DREAM_GPIO_START + 0x08)
> +#define DREAM_GPIO_MISC4_BASE (DREAM_GPIO_START + 0x10)
> +#define DREAM_GPIO_MISC5_BASE (DREAM_GPIO_START + 0x18)
> +#define DREAM_GPIO_INT2_BASE (DREAM_GPIO_START + 0x20)
> +#define DREAM_GPIO_MISC1_BASE (DREAM_GPIO_START + 0x28)
> +#define DREAM_GPIO_VIRTUAL_BASE (DREAM_GPIO_START + 0x30)
> +#define DREAM_GPIO_INT5_BASE (DREAM_GPIO_START + 0x48)
> +
> +#define DREAM_GPIO_CHARGER_EN (DREAM_GPIO_MISC2_BASE + 0)
> +#define DREAM_GPIO_ISET (DREAM_GPIO_MISC2_BASE + 1)
> +#define DREAM_GPIO_H2W_DAT_DIR (DREAM_GPIO_MISC2_BASE + 2)
> +#define DREAM_GPIO_H2W_CLK_DIR (DREAM_GPIO_MISC2_BASE + 3)
> +#define DREAM_GPIO_H2W_DAT_GPO (DREAM_GPIO_MISC2_BASE + 4)
> +#define DREAM_GPIO_H2W_CLK_GPO (DREAM_GPIO_MISC2_BASE + 5)
> +#define DREAM_GPIO_H2W_SEL0 (DREAM_GPIO_MISC2_BASE + 6)
> +#define DREAM_GPIO_H2W_SEL1 (DREAM_GPIO_MISC2_BASE + 7)
> +
> +#define DREAM_GPIO_SPOTLIGHT_EN (DREAM_GPIO_MISC3_BASE + 0)
> +#define DREAM_GPIO_FLASH_EN (DREAM_GPIO_MISC3_BASE + 1)
> +#define DREAM_GPIO_I2C_PULL (DREAM_GPIO_MISC3_BASE + 2)
> +#define DREAM_GPIO_TP_I2C_PULL (DREAM_GPIO_MISC3_BASE + 3)
> +#define DREAM_GPIO_TP_EN (DREAM_GPIO_MISC3_BASE + 4)
> +#define DREAM_GPIO_JOG_EN (DREAM_GPIO_MISC3_BASE + 5)
> +#define DREAM_GPIO_UI_LED_EN (DREAM_GPIO_MISC3_BASE + 6)
> +#define DREAM_GPIO_QTKEY_LED_EN (DREAM_GPIO_MISC3_BASE + 7)
> +
> +#define DREAM_GPIO_VCM_PWDN (DREAM_GPIO_MISC4_BASE + 0)
> +#define DREAM_GPIO_USB_H2W_SW (DREAM_GPIO_MISC4_BASE + 1)
> +#define DREAM_GPIO_COMPASS_RST_N (DREAM_GPIO_MISC4_BASE + 2)
> +#define DREAM_GPIO_HAPTIC_EN_UP (DREAM_GPIO_MISC4_BASE + 3)
> +#define DREAM_GPIO_HAPTIC_EN_MAIN (DREAM_GPIO_MISC4_BASE + 4)
> +#define DREAM_GPIO_USB_PHY_RST_N (DREAM_GPIO_MISC4_BASE + 5)
> +#define DREAM_GPIO_WIFI_PA_RESETX (DREAM_GPIO_MISC4_BASE + 6)
> +#define DREAM_GPIO_WIFI_EN (DREAM_GPIO_MISC4_BASE + 7)
> +
> +#define DREAM_GPIO_BT_32K_EN (DREAM_GPIO_MISC5_BASE + 0)
> +#define DREAM_GPIO_MAC_32K_EN (DREAM_GPIO_MISC5_BASE + 1)
> +#define DREAM_GPIO_MDDI_32K_EN (DREAM_GPIO_MISC5_BASE + 2)
> +#define DREAM_GPIO_COMPASS_32K_EN (DREAM_GPIO_MISC5_BASE + 3)
> +
> +#define DREAM_GPIO_NAVI_ACT_N (DREAM_GPIO_INT2_BASE + 0)
> +#define DREAM_GPIO_COMPASS_IRQ (DREAM_GPIO_INT2_BASE + 1)
> +#define DREAM_GPIO_SLIDING_DET (DREAM_GPIO_INT2_BASE + 2)
> +#define DREAM_GPIO_AUD_HSMIC_DET_N (DREAM_GPIO_INT2_BASE + 3)
> +#define DREAM_GPIO_SD_DOOR_N (DREAM_GPIO_INT2_BASE + 4)
> +#define DREAM_GPIO_CAM_BTN_STEP1_N (DREAM_GPIO_INT2_BASE + 5)
> +#define DREAM_GPIO_CAM_BTN_STEP2_N (DREAM_GPIO_INT2_BASE + 6)
> +#define DREAM_GPIO_TP_ATT_N (DREAM_GPIO_INT2_BASE + 7)
> +#define DREAM_GPIO_BANK0_FIRST_INT_SOURCE (DREAM_GPIO_NAVI_ACT_N)
> +#define DREAM_GPIO_BANK0_LAST_INT_SOURCE (DREAM_GPIO_TP_ATT_N)
> +
> +#define DREAM_GPIO_H2W_DAT_GPI (DREAM_GPIO_MISC1_BASE + 0)
> +#define DREAM_GPIO_H2W_CLK_GPI (DREAM_GPIO_MISC1_BASE + 1)
> +#define DREAM_GPIO_CPLD128_VER_0 (DREAM_GPIO_MISC1_BASE + 4)
> +#define DREAM_GPIO_CPLD128_VER_1 (DREAM_GPIO_MISC1_BASE + 5)
> +#define DREAM_GPIO_CPLD128_VER_2 (DREAM_GPIO_MISC1_BASE + 6)
> +#define DREAM_GPIO_CPLD128_VER_3 (DREAM_GPIO_MISC1_BASE + 7)
> +
> +#define DREAM_GPIO_SDMC_CD_N (DREAM_GPIO_VIRTUAL_BASE + 0)
> +#define DREAM_GPIO_END (DREAM_GPIO_SDMC_CD_N)
> +#define DREAM_GPIO_BANK1_FIRST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
> +#define DREAM_GPIO_BANK1_LAST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
> +
> +#define DREAM_GPIO_VIRTUAL_TO_REAL_OFFSET \
> + (DREAM_GPIO_INT5_BASE - DREAM_GPIO_VIRTUAL_BASE)
> +
> +#define DREAM_INT_START (NR_MSM_IRQS + NR_GPIO_IRQS)
> +#define DREAM_INT_BANK0_COUNT (8)
> +#define DREAM_INT_BANK1_START (DREAM_INT_START + DREAM_INT_BANK0_COUNT)
> +#define DREAM_INT_BANK1_COUNT (1)
> +#define DREAM_INT_END (DREAM_INT_START + DREAM_INT_BANK0_COUNT + \
> + DREAM_INT_BANK1_COUNT - 1)
> +#define DREAM_GPIO_TO_INT(n) (((n) <= DREAM_GPIO_BANK0_LAST_INT_SOURCE) ? \
> + (DREAM_INT_START - DREAM_GPIO_BANK0_FIRST_INT_SOURCE + (n)) : \
> + (DREAM_INT_BANK1_START - DREAM_GPIO_BANK1_FIRST_INT_SOURCE + (n)))
> +
> +#define DREAM_INT_TO_BANK(n) ((n - DREAM_INT_START) / DREAM_INT_BANK0_COUNT)
> +#define DREAM_INT_TO_MASK(n) (1U << ((n - DREAM_INT_START) & 7))
> +#define DREAM_BANK_TO_MASK_REG(bank) \
> + (bank ? DREAM_GPIO_INT_MASK1_REG : DREAM_GPIO_INT_MASK0_REG)
> +#define DREAM_BANK_TO_STAT_REG(bank) \
> + (bank ? DREAM_GPIO_INT_STAT1_REG : DREAM_GPIO_INT_STAT0_REG)

Are these needed outside of the gpiolib code? If not, they should be
moved there. I also think they should have lower case names since they
act like a function, and make the code where they are used nicer to read.

> diff --git a/arch/arm/mach-msm/generic_gpio.c b/arch/arm/mach-msm/generic_gpio.c
> new file mode 100644
> index 0000000..fe24d38
> --- /dev/null
> +++ b/arch/arm/mach-msm/generic_gpio.c
> @@ -0,0 +1,274 @@
> +/* arch/arm/mach-msm/generic_gpio.c
> + *
> + * Copyright (C) 2007 Google, Inc.
> + *
> + * This software is licensed under the terms of the GNU General Public
> + * License version 2, as published by the Free Software Foundation, and
> + * may be copied, distributed, and modified under those terms.
> + *
> + * This program is distributed in the hope that 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/kernel.h>
> +#include <linux/module.h>
> +#include <linux/errno.h>
> +#include <linux/slab.h>
> +#include <linux/spinlock.h>
> +#include <asm/gpio.h>
> +#include "gpio_chip.h"
> +
> +#define GPIO_NUM_TO_CHIP_INDEX(gpio) ((gpio)>>5)
> +
> +struct gpio_state {
> + unsigned long flags;
> + int refcount;
> +};
> +
> +static DEFINE_SPINLOCK(gpio_chips_lock);
> +static LIST_HEAD(gpio_chip_list);
> +static struct gpio_chip **gpio_chip_array;
> +static unsigned long gpio_chip_array_size;
> +
> +int register_gpio_chip(struct gpio_chip *new_gpio_chip)
> +{
> + int err = 0;
> + struct gpio_chip *gpio_chip;
> + int i;
> + unsigned long irq_flags;
> + unsigned int chip_array_start_index, chip_array_end_index;
> +
> + new_gpio_chip->state = kzalloc((new_gpio_chip->end + 1 - new_gpio_chip->start) * sizeof(new_gpio_chip->state[0]), GFP_KERNEL);
> + if (new_gpio_chip->state == NULL) {
> + printk(KERN_ERR "register_gpio_chip: failed to allocate state\n");
> + return -ENOMEM;
> + }
> +
> + spin_lock_irqsave(&gpio_chips_lock, irq_flags);
> + chip_array_start_index = GPIO_NUM_TO_CHIP_INDEX(new_gpio_chip->start);
> + chip_array_end_index = GPIO_NUM_TO_CHIP_INDEX(new_gpio_chip->end);
> + if (chip_array_end_index >= gpio_chip_array_size) {
> + struct gpio_chip **new_gpio_chip_array;
> + unsigned long new_gpio_chip_array_size = chip_array_end_index + 1;
> +
> + new_gpio_chip_array = kmalloc(new_gpio_chip_array_size * sizeof(new_gpio_chip_array[0]), GFP_ATOMIC);
> + if (new_gpio_chip_array == NULL) {
> + printk(KERN_ERR "register_gpio_chip: failed to allocate array\n");
> + err = -ENOMEM;
> + goto failed;
> + }
> + for (i = 0; i < gpio_chip_array_size; i++)
> + new_gpio_chip_array[i] = gpio_chip_array[i];
> + for (i = gpio_chip_array_size; i < new_gpio_chip_array_size; i++)
> + new_gpio_chip_array[i] = NULL;
> + gpio_chip_array = new_gpio_chip_array;
> + gpio_chip_array_size = new_gpio_chip_array_size;
> + }
> + list_for_each_entry(gpio_chip, &gpio_chip_list, list) {
> + if (gpio_chip->start > new_gpio_chip->end) {
> + list_add_tail(&new_gpio_chip->list, &gpio_chip->list);
> + goto added;
> + }
> + if (gpio_chip->end >= new_gpio_chip->start) {
> + printk(KERN_ERR "register_gpio_source %u-%u overlaps with %u-%u\n",
> + new_gpio_chip->start, new_gpio_chip->end,
> + gpio_chip->start, gpio_chip->end);
> + err = -EBUSY;
> + goto failed;
> + }
> + }
> + list_add_tail(&new_gpio_chip->list, &gpio_chip_list);
> +added:
> + for (i = chip_array_start_index; i <= chip_array_end_index; i++) {
> + if (gpio_chip_array[i] == NULL || gpio_chip_array[i]->start > new_gpio_chip->start)
> + gpio_chip_array[i] = new_gpio_chip;
> + }
> +failed:
> + spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
> + if (err)
> + kfree(new_gpio_chip->state);
> + return err;
> +}

Thats big, hard to read, has about 3 blank lines total and no comments.

> +
> +static struct gpio_chip *get_gpio_chip_locked(unsigned int gpio)
> +{
> + unsigned long i;
> + struct gpio_chip *chip;
> +
> + i = GPIO_NUM_TO_CHIP_INDEX(gpio);
> + if (i >= gpio_chip_array_size)
> + return NULL;
> + chip = gpio_chip_array[i];
> + if (chip == NULL)
> + return NULL;
> + list_for_each_entry_from(chip, &gpio_chip_list, list) {
> + if (gpio < chip->start)
> + return NULL;
> + if (gpio <= chip->end)
> + return chip;
> + }
> + return NULL;
> +}
> +
> +static int request_gpio(unsigned int gpio, unsigned long flags)
> +{
> + int err = 0;
> + struct gpio_chip *chip;
> + unsigned long irq_flags;
> + unsigned long chip_index;
> +
> + spin_lock_irqsave(&gpio_chips_lock, irq_flags);
> + chip = get_gpio_chip_locked(gpio);
> + if (chip == NULL) {
> + err = -EINVAL;
> + goto err;
> + }
> + chip_index = gpio - chip->start;
> + if (chip->state[chip_index].refcount == 0) {
> + chip->configure(chip, gpio, flags);
> + chip->state[chip_index].flags = flags;
> + chip->state[chip_index].refcount++;
> + } else if ((flags & IRQF_SHARED) && (chip->state[chip_index].flags & IRQF_SHARED))
> + chip->state[chip_index].refcount++;
> + else
> + err = -EBUSY;
> +err:
> + spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
> + return err;
> +}
> +
> +int gpio_request(unsigned gpio, const char *label)
> +{
> + return request_gpio(gpio, 0);
> +}
> +EXPORT_SYMBOL(gpio_request);
> +
> +void gpio_free(unsigned gpio)
> +{
> + struct gpio_chip *chip;
> + unsigned long irq_flags;
> + unsigned long chip_index;
> +
> + spin_lock_irqsave(&gpio_chips_lock, irq_flags);
> + chip = get_gpio_chip_locked(gpio);
> + if (chip) {
> + chip_index = gpio - chip->start;
> + chip->state[chip_index].refcount--;
> + }
> + spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
> +}
> +EXPORT_SYMBOL(gpio_free);
> +
> +static int gpio_get_irq_num(unsigned int gpio, unsigned int *irqp, unsigned long *irqnumflagsp)
> +{
> + int ret = -ENOTSUPP;
> + struct gpio_chip *chip;
> + unsigned long irq_flags;
> +
> + spin_lock_irqsave(&gpio_chips_lock, irq_flags);
> + chip = get_gpio_chip_locked(gpio);
> + if (chip && chip->get_irq_num)
> + ret = chip->get_irq_num(chip, gpio, irqp, irqnumflagsp);
> + spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
> + return ret;
> +}
> +
> +int gpio_to_irq(unsigned gpio)
> +{
> + int ret, irq;
> + ret = gpio_get_irq_num(gpio, &irq, NULL);
> + if (ret)
> + return ret;
> + return irq;
> +}
> +EXPORT_SYMBOL(gpio_to_irq);
> +
> +int gpio_configure(unsigned int gpio, unsigned long flags)
> +{
> + int ret = -ENOTSUPP;
> + struct gpio_chip *chip;
> + unsigned long irq_flags;
> +
> + spin_lock_irqsave(&gpio_chips_lock, irq_flags);
> + chip = get_gpio_chip_locked(gpio);
> + if (chip)
> + ret = chip->configure(chip, gpio, flags);
> + spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
> + return ret;
> +}
> +EXPORT_SYMBOL(gpio_configure);
> +
> +int gpio_direction_input(unsigned gpio)
> +{
> + return gpio_configure(gpio, GPIOF_INPUT);
> +}
> +EXPORT_SYMBOL(gpio_direction_input);
> +
> +int gpio_direction_output(unsigned gpio, int value)
> +{
> + gpio_set_value(gpio, value);
> + return gpio_configure(gpio, GPIOF_DRIVE_OUTPUT);
> +}
> +EXPORT_SYMBOL(gpio_direction_output);
> +
> +int gpio_get_value(unsigned gpio)
> +{
> + int ret = -ENOTSUPP;
> + struct gpio_chip *chip;
> + unsigned long irq_flags;
> +
> + spin_lock_irqsave(&gpio_chips_lock, irq_flags);
> + chip = get_gpio_chip_locked(gpio);
> + if (chip && chip->read)
> + ret = chip->read(chip, gpio);
> + spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
> + return ret;
> +}
> +EXPORT_SYMBOL(gpio_get_value);
> +
> +void gpio_set_value(unsigned gpio, int on)
> +{
> + int ret = -ENOTSUPP;
> + struct gpio_chip *chip;
> + unsigned long irq_flags;
> +
> + spin_lock_irqsave(&gpio_chips_lock, irq_flags);
> + chip = get_gpio_chip_locked(gpio);
> + if (chip && chip->write)
> + ret = chip->write(chip, gpio, on);
> + spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
> +}
> +EXPORT_SYMBOL(gpio_set_value);
> +
> +int gpio_read_detect_status(unsigned int gpio)
> +{
> + int ret = -ENOTSUPP;
> + struct gpio_chip *chip;
> + unsigned long irq_flags;
> +
> + spin_lock_irqsave(&gpio_chips_lock, irq_flags);
> + chip = get_gpio_chip_locked(gpio);
> + if (chip && chip->read_detect_status)
> + ret = chip->read_detect_status(chip, gpio);
> + spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
> + return ret;
> +}
> +EXPORT_SYMBOL(gpio_read_detect_status);
> +
> +int gpio_clear_detect_status(unsigned int gpio)
> +{
> + int ret = -ENOTSUPP;
> + struct gpio_chip *chip;
> + unsigned long irq_flags;
> +
> + spin_lock_irqsave(&gpio_chips_lock, irq_flags);
> + chip = get_gpio_chip_locked(gpio);
> + if (chip && chip->clear_detect_status)
> + ret = chip->clear_detect_status(chip, gpio);
> + spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
> + return ret;
> +}
> +EXPORT_SYMBOL(gpio_clear_detect_status);
> diff --git a/arch/arm/mach-msm/gpio_chip.h b/arch/arm/mach-msm/gpio_chip.h
> new file mode 100644
> index 0000000..ee4eddc
> --- /dev/null
> +++ b/arch/arm/mach-msm/gpio_chip.h
> @@ -0,0 +1,50 @@
> +/* arch/arm/mach-msm/gpio_chip.h
> + *
> + * Copyright (C) 2007 Google, Inc.
> + *
> + * This software is licensed under the terms of the GNU General Public
> + * License version 2, as published by the Free Software Foundation, and
> + * may be copied, distributed, and modified under those terms.
> + *
> + * This program is distributed in the hope that 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.
> + *
> + */
> +
> +#ifndef _LINUX_GPIO_CHIP_H
> +#define _LINUX_GPIO_CHIP_H
> +
> +#include <linux/list.h>
> +
> +struct gpio_chip {
> + struct list_head list;
> + struct gpio_state *state;
> +
> + unsigned int start;
> + unsigned int end;
> +
> + int (*configure)(struct gpio_chip *chip, unsigned int gpio, unsigned long flags);
> + int (*get_irq_num)(struct gpio_chip *chip, unsigned int gpio, unsigned int *irqp, unsigned long *irqnumflagsp);
> + int (*read)(struct gpio_chip *chip, unsigned int gpio);
> + int (*write)(struct gpio_chip *chip, unsigned int gpio, unsigned on);
> + int (*read_detect_status)(struct gpio_chip *chip, unsigned int gpio);
> + int (*clear_detect_status)(struct gpio_chip *chip, unsigned int gpio);
> +};
> +
> +int register_gpio_chip(struct gpio_chip *gpio_chip);
> +
> +/* extended gpio api */
> +
> +#define GPIOF_IRQF_MASK 0x0000ffff /* use to specify edge detection without */
> +#define GPIOF_IRQF_TRIGGER_NONE 0x00010000 /* IRQF_TRIGGER_NONE is 0 which also means "as already configured" */
> +#define GPIOF_INPUT 0x00020000
> +#define GPIOF_DRIVE_OUTPUT 0x00040000
> +#define GPIOF_OUTPUT_LOW 0x00080000
> +#define GPIOF_OUTPUT_HIGH 0x00100000
> +
> +#define GPIOIRQF_SHARED 0x00000001 /* the irq line is shared with other inputs */
> +
> +
> +#endif
> diff --git a/arch/arm/mach-msm/include/mach/gpio.h b/arch/arm/mach-msm/include/mach/gpio.h
> new file mode 100644
> index 0000000..92ce18d
> --- /dev/null
> +++ b/arch/arm/mach-msm/include/mach/gpio.h
> @@ -0,0 +1,36 @@
> +/* linux/include/asm-arm/arch-msm/gpio.h
> + *
> + * Copyright (C) 2007 Google, Inc.
> + * Author: Mike Lockwood <[email protected]>
> + *
> + * This software is licensed under the terms of the GNU General Public
> + * License version 2, as published by the Free Software Foundation, and
> + * may be copied, distributed, and modified under those terms.
> + *
> + * This program is distributed in the hope that 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.
> + *
> + */
> +
> +#ifndef __ASM_ARCH_MSM_GPIO_H
> +#define __ASM_ARCH_MSM_GPIO_H
> +
> +#include <linux/interrupt.h>
> +
> +int gpio_request(unsigned gpio, const char *label);
> +void gpio_free(unsigned gpio);
> +int gpio_direction_input(unsigned gpio);
> +int gpio_direction_output(unsigned gpio, int value);
> +int gpio_get_value(unsigned gpio);
> +void gpio_set_value(unsigned gpio, int value);
> +int gpio_to_irq(unsigned gpio);
> +
> +#include <asm-generic/gpio.h>
> +
> +extern int gpio_configure(unsigned int gpio, unsigned long flags);
> +extern int gpio_read_detect_status(unsigned int gpio);
> +extern int gpio_clear_detect_status(unsigned int gpio);
> +
> +#endif
>
>


--
Bluewater Systems Ltd - ARM Technology Solution Centre

Ryan Mallon 5 Amuri Park, 404 Barbadoes St
[email protected] PO Box 13 889, Christchurch 8013
http://www.bluewatersys.com New Zealand
Phone: +64 3 3779127 Freecall: Australia 1800 148 751
Fax: +64 3 3779135 USA 1800 261 2934

2009-12-08 21:37:35

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

Hi!

> > +#undef MODULE_PARAM_PREFIX
> > +#define MODULE_PARAM_PREFIX "board_dream."
>
> This looks a bit dodgy. Is this
> (http://lkml.indiana.edu/hypermail/linux/kernel/0903.0/02768.html) the
> preferred way?

I don't think that would help that much here....

> > +static void update_pwrsink(unsigned gpio, unsigned on)
> > +{
> > + switch(gpio) {
> > + case DREAM_GPIO_UI_LED_EN:
> > + break;
> > + case DREAM_GPIO_QTKEY_LED_EN:
> > + break;
> > + }
> > +}
>
> What is this function for?

Power accounting... should be removed. Fixed.

> > +static void dream_gpio_irq_ack(unsigned int irq)
> > +{
> > + int bank = DREAM_INT_TO_BANK(irq);
> > + uint8_t mask = DREAM_INT_TO_MASK(irq);
> > + int reg = DREAM_BANK_TO_STAT_REG(bank);
> > + /*printk(KERN_INFO "dream_gpio_irq_ack irq %d\n", irq);*/
>
> pr_debug, or just remove it?

Remove.

> > + desc->chip->ack(irq);
> > +}
>
> Some blank lines here and there would make this more readable. All your
> code is wedged together :-).

Well, added some blank lines; not sure it is improvement.

> > +#define DREAM_INT_TO_BANK(n) ((n - DREAM_INT_START) / DREAM_INT_BANK0_COUNT)
> > +#define DREAM_INT_TO_MASK(n) (1U << ((n - DREAM_INT_START) & 7))
> > +#define DREAM_BANK_TO_MASK_REG(bank) \
> > + (bank ? DREAM_GPIO_INT_MASK1_REG : DREAM_GPIO_INT_MASK0_REG)
> > +#define DREAM_BANK_TO_STAT_REG(bank) \
> > + (bank ? DREAM_GPIO_INT_STAT1_REG : DREAM_GPIO_INT_STAT0_REG)
>
> Are these needed outside of the gpiolib code? If not, they should be
> moved there. I also think they should have lower case names since they
> act like a function, and make the code where they are used nicer to
> read.

I guess these logically belong here.

No, macros are macros, that means upcase.

> > + spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
> > + if (err)
> > + kfree(new_gpio_chip->state);
> > + return err;
> > +}
>
> Thats big, hard to read, has about 3 blank lines total and no comments.

I tried to improve it, but it needs more. Here are my cleanups.
Pavel

diff --git a/arch/arm/mach-msm/board-dream-gpio.c b/arch/arm/mach-msm/board-dream-gpio.c
index 1b23a84..7796254 100644
--- a/arch/arm/mach-msm/board-dream-gpio.c
+++ b/arch/arm/mach-msm/board-dream-gpio.c
@@ -18,7 +18,7 @@
#include <linux/irq.h>
#include <linux/pm.h>
#include <linux/sysdev.h>
-#include <linux/io.h>
+#include <linux/io.h>

#include <asm/gpio.h>
#include <asm/mach-types.h>
@@ -35,21 +35,21 @@ module_param_named(usb_h2w_sw, cpld_usb_h2w_sw, uint, 0);
static uint8_t dream_cpld_shadow[4] = {
#if defined(CONFIG_MSM_DEBUG_UART1)
/* H2W pins <-> UART1 */
- [0] = 0x40, // for serial debug, low current
+ [0] = 0x40, /* for serial debug, low current */
#else
/* H2W pins <-> UART3, Bluetooth <-> UART1 */
- [0] = 0x80, // for serial debug, low current
+ [0] = 0x80, /* for serial debug, low current */
#endif
- [1] = 0x04, // I2C_PULL
- [3] = 0x04, // mmdi 32k en
+ [1] = 0x04, /* I2C_PULL */
+ [3] = 0x04, /* mmdi 32k en */
};
static uint8_t dream_int_mask[2] = {
- [0] = 0xff, /* mask all interrupts */
- [1] = 0xff,
+ [0] = 0xff, /* mask all interrupts */
+ [1] = 0xff,
};
static uint8_t dream_sleep_int_mask[] = {
- [0] = 0xff,
- [1] = 0xff,
+ [0] = 0xff,
+ [1] = 0xff,
};
static int dream_suspended;

@@ -60,26 +60,16 @@ static int dream_gpio_read(struct gpio_chip *chip, unsigned n)
if (n >= DREAM_GPIO_VIRTUAL_BASE)
n += DREAM_GPIO_VIRTUAL_TO_REAL_OFFSET;
b = 1U << (n & 7);
- reg = (n & 0x78) >> 2; // assumes base is 128
+ reg = (n & 0x78) >> 2; /* assumes base is 128 */
return !!(readb(DREAM_CPLD_BASE + reg) & b);
}

-static void update_pwrsink(unsigned gpio, unsigned on)
-{
- switch(gpio) {
- case DREAM_GPIO_UI_LED_EN:
- break;
- case DREAM_GPIO_QTKEY_LED_EN:
- break;
- }
-}
-
static uint8_t dream_gpio_write_shadow(unsigned n, unsigned on)
{
uint8_t b = 1U << (n & 7);
- int reg = (n & 0x78) >> 2; // assumes base is 128
+ int reg = (n & 0x78) >> 2; /* assumes base is 128 */

- if(on)
+ if (on)
return dream_cpld_shadow[reg >> 1] |= b;
else
return dream_cpld_shadow[reg >> 1] &= ~b;
@@ -87,7 +77,7 @@ static uint8_t dream_gpio_write_shadow(unsigned n, unsigned on)

static int dream_gpio_write(struct gpio_chip *chip, unsigned n, unsigned on)
{
- int reg = (n & 0x78) >> 2; // assumes base is 128
+ int reg = (n & 0x78) >> 2; /* assumes base is 128 */
unsigned long flags;
uint8_t reg_val;

@@ -97,7 +87,6 @@ static int dream_gpio_write(struct gpio_chip *chip, unsigned n, unsigned on)
}

local_irq_save(flags);
- update_pwrsink(n, on);
reg_val = dream_gpio_write_shadow(n, on);
writeb(reg_val, DREAM_CPLD_BASE + reg);
local_irq_restore(flags);
@@ -106,7 +95,7 @@ static int dream_gpio_write(struct gpio_chip *chip, unsigned n, unsigned on)

static int dream_gpio_configure(struct gpio_chip *chip, unsigned int gpio, unsigned long flags)
{
- if(flags & (GPIOF_OUTPUT_LOW | GPIOF_OUTPUT_HIGH))
+ if (flags & (GPIOF_OUTPUT_LOW | GPIOF_OUTPUT_HIGH))
dream_gpio_write(chip, gpio, flags & GPIOF_OUTPUT_HIGH);
return 0;
}
@@ -119,7 +108,7 @@ static int dream_gpio_get_irq_num(struct gpio_chip *chip, unsigned int gpio, uns
gpio > DREAM_GPIO_BANK1_LAST_INT_SOURCE))
return -ENOENT;
*irqp = DREAM_GPIO_TO_INT(gpio);
- if(irqnumflagsp)
+ if (irqnumflagsp)
*irqnumflagsp = 0;
return 0;
}
@@ -129,7 +118,7 @@ static void dream_gpio_irq_ack(unsigned int irq)
int bank = DREAM_INT_TO_BANK(irq);
uint8_t mask = DREAM_INT_TO_MASK(irq);
int reg = DREAM_BANK_TO_STAT_REG(bank);
- /*printk(KERN_INFO "dream_gpio_irq_ack irq %d\n", irq);*/
+
writeb(mask, DREAM_CPLD_BASE + reg);
}

@@ -143,8 +132,7 @@ static void dream_gpio_irq_mask(unsigned int irq)

local_irq_save(flags);
reg_val = dream_int_mask[bank] |= mask;
- /*printk(KERN_INFO "dream_gpio_irq_mask irq %d => %d:%02x\n",
- irq, bank, reg_val);*/
+
if (!dream_suspended)
writeb(reg_val, DREAM_CPLD_BASE + reg);
local_irq_restore(flags);
@@ -160,8 +148,7 @@ static void dream_gpio_irq_unmask(unsigned int irq)

local_irq_save(flags);
reg_val = dream_int_mask[bank] &= ~mask;
- /*printk(KERN_INFO "dream_gpio_irq_unmask irq %d => %d:%02x\n",
- irq, bank, reg_val);*/
+
if (!dream_suspended)
writeb(reg_val, DREAM_CPLD_BASE + reg);
local_irq_restore(flags);
@@ -174,7 +161,7 @@ int dream_gpio_irq_set_wake(unsigned int irq, unsigned int on)
uint8_t mask = DREAM_INT_TO_MASK(irq);

local_irq_save(flags);
- if(on)
+ if (on)
dream_sleep_int_mask[bank] &= ~mask;
else
dream_sleep_int_mask[bank] |= mask;
@@ -195,17 +182,17 @@ static void dream_gpio_irq_handler(unsigned int irq, struct irq_desc *desc)
stat_reg = DREAM_BANK_TO_STAT_REG(bank);
v = readb(DREAM_CPLD_BASE + stat_reg);
int_mask = dream_int_mask[bank];
+
if (v & int_mask) {
writeb(v & int_mask, DREAM_CPLD_BASE + stat_reg);
printk(KERN_ERR "dream_gpio_irq_handler: got masked "
"interrupt: %d:%02x\n", bank, v & int_mask);
}
+
v &= ~int_mask;
while (v) {
m = v & -v;
j = fls(m) - 1;
- /*printk(KERN_INFO "msm_gpio_irq_handler %d:%02x %02x b"
- "it %d irq %d\n", bank, v, m, j, int_base + j);*/
v &= ~m;
generic_handle_irq(int_base + j);
}
@@ -242,7 +229,6 @@ static struct irq_chip dream_gpio_irq_chip = {
.mask = dream_gpio_irq_mask,
.unmask = dream_gpio_irq_unmask,
.set_wake = dream_gpio_irq_set_wake,
- //.set_type = dream_gpio_irq_set_type,
};

static struct gpio_chip dream_gpio_chip = {
@@ -252,8 +238,6 @@ static struct gpio_chip dream_gpio_chip = {
.get_irq_num = dream_gpio_get_irq_num,
.read = dream_gpio_read,
.write = dream_gpio_write,
-// .read_detect_status = dream_gpio_read_detect_status,
-// .clear_detect_status = dream_gpio_clear_detect_status
};

struct sysdev_class dream_sysdev_class = {
@@ -277,10 +261,10 @@ static int __init dream_init_gpio(void)
pr_info("dream_init_gpio: cpld_usb_hw2_sw = %d\n", cpld_usb_h2w_sw);
dream_gpio_write_shadow(DREAM_GPIO_USB_H2W_SW, cpld_usb_h2w_sw);

- for(i = 0; i < ARRAY_SIZE(dream_cpld_shadow); i++)
+ for (i = 0; i < ARRAY_SIZE(dream_cpld_shadow); i++)
writeb(dream_cpld_shadow[i], DREAM_CPLD_BASE + i * 2);

- for(i = DREAM_INT_START; i <= DREAM_INT_END; i++) {
+ for (i = DREAM_INT_START; i <= DREAM_INT_END; i++) {
set_irq_chip(i, &dream_gpio_irq_chip);
set_irq_handler(i, handle_edge_irq);
set_irq_flags(i, IRQF_VALID);
@@ -292,7 +276,7 @@ static int __init dream_init_gpio(void)
set_irq_chained_handler(MSM_GPIO_TO_INT(17), dream_gpio_irq_handler);
set_irq_wake(MSM_GPIO_TO_INT(17), 1);

- if(sysdev_class_register(&dream_sysdev_class) == 0)
+ if (sysdev_class_register(&dream_sysdev_class) == 0)
sysdev_register(&dream_irq_device);

return 0;
diff --git a/arch/arm/mach-msm/board-dream.c b/arch/arm/mach-msm/board-dream.c
index 4758957..3e8e54a 100644
--- a/arch/arm/mach-msm/board-dream.c
+++ b/arch/arm/mach-msm/board-dream.c
@@ -59,6 +59,23 @@ static void __init dream_fixup(struct machine_desc *desc, struct tag *tags,

static void __init dream_init(void)
{
+ gpio_set_value(DREAM_GPIO_UI_LED_EN, 1);
+ mdelay(300);
+ gpio_set_value(DREAM_GPIO_UI_LED_EN, 0);
+ mdelay(300);
+ gpio_set_value(DREAM_GPIO_UI_LED_EN, 1);
+ mdelay(300);
+ gpio_set_value(DREAM_GPIO_UI_LED_EN, 0);
+ mdelay(300);
+ gpio_set_value(DREAM_GPIO_UI_LED_EN, 1);
+ mdelay(300);
+ gpio_set_value(DREAM_GPIO_UI_LED_EN, 0);
+ mdelay(300);
+ gpio_set_value(DREAM_GPIO_UI_LED_EN, 1);
+ mdelay(300);
+ gpio_set_value(DREAM_GPIO_UI_LED_EN, 0);
+ mdelay(300);
+
platform_add_devices(devices, ARRAY_SIZE(devices));
}

diff --git a/arch/arm/mach-msm/generic_gpio.c b/arch/arm/mach-msm/generic_gpio.c
index fe24d38..cde1685 100644
--- a/arch/arm/mach-msm/generic_gpio.c
+++ b/arch/arm/mach-msm/generic_gpio.c
@@ -40,8 +40,10 @@ int register_gpio_chip(struct gpio_chip *new_gpio_chip)
int i;
unsigned long irq_flags;
unsigned int chip_array_start_index, chip_array_end_index;
+ int size = (new_gpio_chip->end + 1 - new_gpio_chip->start) *
+ sizeof(new_gpio_chip->state[0]);

- new_gpio_chip->state = kzalloc((new_gpio_chip->end + 1 - new_gpio_chip->start) * sizeof(new_gpio_chip->state[0]), GFP_KERNEL);
+ new_gpio_chip->state = kzalloc(size, GFP_KERNEL);
if (new_gpio_chip->state == NULL) {
printk(KERN_ERR "register_gpio_chip: failed to allocate state\n");
return -ENOMEM;
@@ -50,12 +52,13 @@ int register_gpio_chip(struct gpio_chip *new_gpio_chip)
spin_lock_irqsave(&gpio_chips_lock, irq_flags);
chip_array_start_index = GPIO_NUM_TO_CHIP_INDEX(new_gpio_chip->start);
chip_array_end_index = GPIO_NUM_TO_CHIP_INDEX(new_gpio_chip->end);
+
if (chip_array_end_index >= gpio_chip_array_size) {
struct gpio_chip **new_gpio_chip_array;
unsigned long new_gpio_chip_array_size = chip_array_end_index + 1;

new_gpio_chip_array = kmalloc(new_gpio_chip_array_size * sizeof(new_gpio_chip_array[0]), GFP_ATOMIC);
- if (new_gpio_chip_array == NULL) {
+ if (!new_gpio_chip_array) {
printk(KERN_ERR "register_gpio_chip: failed to allocate array\n");
err = -ENOMEM;
goto failed;
@@ -67,6 +70,7 @@ int register_gpio_chip(struct gpio_chip *new_gpio_chip)
gpio_chip_array = new_gpio_chip_array;
gpio_chip_array_size = new_gpio_chip_array_size;
}
+
list_for_each_entry(gpio_chip, &gpio_chip_list, list) {
if (gpio_chip->start > new_gpio_chip->end) {
list_add_tail(&new_gpio_chip->list, &gpio_chip->list);
@@ -80,10 +84,11 @@ int register_gpio_chip(struct gpio_chip *new_gpio_chip)
goto failed;
}
}
+
list_add_tail(&new_gpio_chip->list, &gpio_chip_list);
added:
for (i = chip_array_start_index; i <= chip_array_end_index; i++) {
- if (gpio_chip_array[i] == NULL || gpio_chip_array[i]->start > new_gpio_chip->start)
+ if ((!gpio_chip_array[i]) || gpio_chip_array[i]->start > new_gpio_chip->start)
gpio_chip_array[i] = new_gpio_chip;
}
failed:

--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-08 21:47:18

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

Add GPIO support for HTC Dream.

Signed-off-by: Pavel Machek <[email protected]>

---

On Wed 2009-12-09 09:22:21, Ryan Mallon wrote:
> Pavel Machek wrote:
> > Add GPIO support for HTC Dream.
> >
> > Signed-off-by: Pavel Machek <[email protected]>
>
> You might want to run this through checkpatch, I suspect it is going to
> give you several errors. Some other comments inline.

Yep, fixed. I got the ugly/big function into better shape, too.

diff --git a/arch/arm/mach-msm/Kconfig b/arch/arm/mach-msm/Kconfig
index f780086..774c50e 100644
--- a/arch/arm/mach-msm/Kconfig
+++ b/arch/arm/mach-msm/Kconfig
@@ -40,4 +40,8 @@ config MACH_TROUT
help
Support for the HTC Dream, T-Mobile G1, Android ADP1 devices.

+config GENERIC_GPIO
+ bool
+ default y
+
endif
diff --git a/arch/arm/mach-msm/Makefile b/arch/arm/mach-msm/Makefile
index 91e6f5c..4c2567e 100644
--- a/arch/arm/mach-msm/Makefile
+++ b/arch/arm/mach-msm/Makefile
@@ -6,4 +6,4 @@ obj-y += clock.o clock-7x01a.o

obj-$(CONFIG_MACH_HALIBUT) += board-halibut.o

-obj-$(CONFIG_MACH_TROUT) += board-dream.o
+obj-$(CONFIG_MACH_TROUT) += board-dream.o board-dream-gpio.o generic_gpio.o
diff --git a/arch/arm/mach-msm/board-dream-gpio.c b/arch/arm/mach-msm/board-dream-gpio.c
new file mode 100644
index 0000000..7796254
--- /dev/null
+++ b/arch/arm/mach-msm/board-dream-gpio.c
@@ -0,0 +1,285 @@
+/* arch/arm/mach-msm/board-dream-gpio.c
+ *
+ * Copyright (C) 2008 Google, Inc.
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that 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/kernel.h>
+#include <linux/errno.h>
+#include <linux/irq.h>
+#include <linux/pm.h>
+#include <linux/sysdev.h>
+#include <linux/io.h>
+
+#include <asm/gpio.h>
+#include <asm/mach-types.h>
+
+#include "board-dream.h"
+#include "gpio_chip.h"
+
+#undef MODULE_PARAM_PREFIX
+#define MODULE_PARAM_PREFIX "board_dream."
+
+static uint cpld_usb_h2w_sw;
+module_param_named(usb_h2w_sw, cpld_usb_h2w_sw, uint, 0);
+
+static uint8_t dream_cpld_shadow[4] = {
+#if defined(CONFIG_MSM_DEBUG_UART1)
+ /* H2W pins <-> UART1 */
+ [0] = 0x40, /* for serial debug, low current */
+#else
+ /* H2W pins <-> UART3, Bluetooth <-> UART1 */
+ [0] = 0x80, /* for serial debug, low current */
+#endif
+ [1] = 0x04, /* I2C_PULL */
+ [3] = 0x04, /* mmdi 32k en */
+};
+static uint8_t dream_int_mask[2] = {
+ [0] = 0xff, /* mask all interrupts */
+ [1] = 0xff,
+};
+static uint8_t dream_sleep_int_mask[] = {
+ [0] = 0xff,
+ [1] = 0xff,
+};
+static int dream_suspended;
+
+static int dream_gpio_read(struct gpio_chip *chip, unsigned n)
+{
+ uint8_t b;
+ int reg;
+ if (n >= DREAM_GPIO_VIRTUAL_BASE)
+ n += DREAM_GPIO_VIRTUAL_TO_REAL_OFFSET;
+ b = 1U << (n & 7);
+ reg = (n & 0x78) >> 2; /* assumes base is 128 */
+ return !!(readb(DREAM_CPLD_BASE + reg) & b);
+}
+
+static uint8_t dream_gpio_write_shadow(unsigned n, unsigned on)
+{
+ uint8_t b = 1U << (n & 7);
+ int reg = (n & 0x78) >> 2; /* assumes base is 128 */
+
+ if (on)
+ return dream_cpld_shadow[reg >> 1] |= b;
+ else
+ return dream_cpld_shadow[reg >> 1] &= ~b;
+}
+
+static int dream_gpio_write(struct gpio_chip *chip, unsigned n, unsigned on)
+{
+ int reg = (n & 0x78) >> 2; /* assumes base is 128 */
+ unsigned long flags;
+ uint8_t reg_val;
+
+ if ((reg >> 1) >= ARRAY_SIZE(dream_cpld_shadow)) {
+ printk(KERN_ERR "dream_gpio_write called on input %d\n", n);
+ return -ENOTSUPP;
+ }
+
+ local_irq_save(flags);
+ reg_val = dream_gpio_write_shadow(n, on);
+ writeb(reg_val, DREAM_CPLD_BASE + reg);
+ local_irq_restore(flags);
+ return 0;
+}
+
+static int dream_gpio_configure(struct gpio_chip *chip, unsigned int gpio, unsigned long flags)
+{
+ if (flags & (GPIOF_OUTPUT_LOW | GPIOF_OUTPUT_HIGH))
+ dream_gpio_write(chip, gpio, flags & GPIOF_OUTPUT_HIGH);
+ return 0;
+}
+
+static int dream_gpio_get_irq_num(struct gpio_chip *chip, unsigned int gpio, unsigned int *irqp, unsigned long *irqnumflagsp)
+{
+ if ((gpio < DREAM_GPIO_BANK0_FIRST_INT_SOURCE ||
+ gpio > DREAM_GPIO_BANK0_LAST_INT_SOURCE) &&
+ (gpio < DREAM_GPIO_BANK1_FIRST_INT_SOURCE ||
+ gpio > DREAM_GPIO_BANK1_LAST_INT_SOURCE))
+ return -ENOENT;
+ *irqp = DREAM_GPIO_TO_INT(gpio);
+ if (irqnumflagsp)
+ *irqnumflagsp = 0;
+ return 0;
+}
+
+static void dream_gpio_irq_ack(unsigned int irq)
+{
+ int bank = DREAM_INT_TO_BANK(irq);
+ uint8_t mask = DREAM_INT_TO_MASK(irq);
+ int reg = DREAM_BANK_TO_STAT_REG(bank);
+
+ writeb(mask, DREAM_CPLD_BASE + reg);
+}
+
+static void dream_gpio_irq_mask(unsigned int irq)
+{
+ unsigned long flags;
+ uint8_t reg_val;
+ int bank = DREAM_INT_TO_BANK(irq);
+ uint8_t mask = DREAM_INT_TO_MASK(irq);
+ int reg = DREAM_BANK_TO_MASK_REG(bank);
+
+ local_irq_save(flags);
+ reg_val = dream_int_mask[bank] |= mask;
+
+ if (!dream_suspended)
+ writeb(reg_val, DREAM_CPLD_BASE + reg);
+ local_irq_restore(flags);
+}
+
+static void dream_gpio_irq_unmask(unsigned int irq)
+{
+ unsigned long flags;
+ uint8_t reg_val;
+ int bank = DREAM_INT_TO_BANK(irq);
+ uint8_t mask = DREAM_INT_TO_MASK(irq);
+ int reg = DREAM_BANK_TO_MASK_REG(bank);
+
+ local_irq_save(flags);
+ reg_val = dream_int_mask[bank] &= ~mask;
+
+ if (!dream_suspended)
+ writeb(reg_val, DREAM_CPLD_BASE + reg);
+ local_irq_restore(flags);
+}
+
+int dream_gpio_irq_set_wake(unsigned int irq, unsigned int on)
+{
+ unsigned long flags;
+ int bank = DREAM_INT_TO_BANK(irq);
+ uint8_t mask = DREAM_INT_TO_MASK(irq);
+
+ local_irq_save(flags);
+ if (on)
+ dream_sleep_int_mask[bank] &= ~mask;
+ else
+ dream_sleep_int_mask[bank] |= mask;
+ local_irq_restore(flags);
+ return 0;
+}
+
+static void dream_gpio_irq_handler(unsigned int irq, struct irq_desc *desc)
+{
+ int j, m;
+ unsigned v;
+ int bank;
+ int stat_reg;
+ int int_base = DREAM_INT_START;
+ uint8_t int_mask;
+
+ for (bank = 0; bank < 2; bank++) {
+ stat_reg = DREAM_BANK_TO_STAT_REG(bank);
+ v = readb(DREAM_CPLD_BASE + stat_reg);
+ int_mask = dream_int_mask[bank];
+
+ if (v & int_mask) {
+ writeb(v & int_mask, DREAM_CPLD_BASE + stat_reg);
+ printk(KERN_ERR "dream_gpio_irq_handler: got masked "
+ "interrupt: %d:%02x\n", bank, v & int_mask);
+ }
+
+ v &= ~int_mask;
+ while (v) {
+ m = v & -v;
+ j = fls(m) - 1;
+ v &= ~m;
+ generic_handle_irq(int_base + j);
+ }
+ int_base += DREAM_INT_BANK0_COUNT;
+ }
+ desc->chip->ack(irq);
+}
+
+static int dream_sysdev_suspend(struct sys_device *dev, pm_message_t state)
+{
+ dream_suspended = 1;
+ writeb(dream_sleep_int_mask[0],
+ DREAM_CPLD_BASE + DREAM_GPIO_INT_MASK0_REG);
+ writeb(dream_sleep_int_mask[1],
+ DREAM_CPLD_BASE + DREAM_GPIO_INT_MASK1_REG);
+ writeb(dream_sleep_int_mask[0],
+ DREAM_CPLD_BASE + DREAM_GPIO_INT_STAT0_REG);
+ writeb(dream_sleep_int_mask[1],
+ DREAM_CPLD_BASE + DREAM_GPIO_INT_STAT1_REG);
+ return 0;
+}
+
+int dream_sysdev_resume(struct sys_device *dev)
+{
+ writeb(dream_int_mask[0], DREAM_CPLD_BASE + DREAM_GPIO_INT_MASK0_REG);
+ writeb(dream_int_mask[1], DREAM_CPLD_BASE + DREAM_GPIO_INT_MASK1_REG);
+ dream_suspended = 0;
+ return 0;
+}
+
+static struct irq_chip dream_gpio_irq_chip = {
+ .name = "dreamgpio",
+ .ack = dream_gpio_irq_ack,
+ .mask = dream_gpio_irq_mask,
+ .unmask = dream_gpio_irq_unmask,
+ .set_wake = dream_gpio_irq_set_wake,
+};
+
+static struct gpio_chip dream_gpio_chip = {
+ .start = DREAM_GPIO_START,
+ .end = DREAM_GPIO_END,
+ .configure = dream_gpio_configure,
+ .get_irq_num = dream_gpio_get_irq_num,
+ .read = dream_gpio_read,
+ .write = dream_gpio_write,
+};
+
+struct sysdev_class dream_sysdev_class = {
+ .name = "dreamgpio_irq",
+ .suspend = dream_sysdev_suspend,
+ .resume = dream_sysdev_resume,
+};
+
+static struct sys_device dream_irq_device = {
+ .cls = &dream_sysdev_class,
+};
+
+static int __init dream_init_gpio(void)
+{
+ int i;
+
+ if (!machine_is_trout())
+ return 0;
+
+ /* adjust GPIOs based on bootloader request */
+ pr_info("dream_init_gpio: cpld_usb_hw2_sw = %d\n", cpld_usb_h2w_sw);
+ dream_gpio_write_shadow(DREAM_GPIO_USB_H2W_SW, cpld_usb_h2w_sw);
+
+ for (i = 0; i < ARRAY_SIZE(dream_cpld_shadow); i++)
+ writeb(dream_cpld_shadow[i], DREAM_CPLD_BASE + i * 2);
+
+ for (i = DREAM_INT_START; i <= DREAM_INT_END; i++) {
+ set_irq_chip(i, &dream_gpio_irq_chip);
+ set_irq_handler(i, handle_edge_irq);
+ set_irq_flags(i, IRQF_VALID);
+ }
+
+ register_gpio_chip(&dream_gpio_chip);
+
+ set_irq_type(MSM_GPIO_TO_INT(17), IRQF_TRIGGER_HIGH);
+ set_irq_chained_handler(MSM_GPIO_TO_INT(17), dream_gpio_irq_handler);
+ set_irq_wake(MSM_GPIO_TO_INT(17), 1);
+
+ if (sysdev_class_register(&dream_sysdev_class) == 0)
+ sysdev_register(&dream_irq_device);
+
+ return 0;
+}
+
+postcore_initcall(dream_init_gpio);
diff --git a/arch/arm/mach-msm/board-dream.c b/arch/arm/mach-msm/board-dream.c
index d238e2c..3e8e54a 100644
--- a/arch/arm/mach-msm/board-dream.c
+++ b/arch/arm/mach-msm/board-dream.c
@@ -18,11 +18,13 @@
#include <linux/kernel.h>
#include <linux/init.h>
#include <linux/platform_device.h>
+#include <linux/delay.h>

#include <asm/mach-types.h>
#include <asm/mach/arch.h>
#include <asm/mach/map.h>
#include <asm/setup.h>
+#include <asm/gpio.h>

#include <mach/board.h>
#include <mach/hardware.h>
@@ -57,14 +59,14 @@ static void __init dream_fixup(struct machine_desc *desc, struct tag *tags,

static void __init dream_init(void)
{
platform_add_devices(devices, ARRAY_SIZE(devices));
}

static struct map_desc dream_io_desc[] __initdata = {
{
- .virtual = TROUT_CPLD_BASE,
- .pfn = __phys_to_pfn(TROUT_CPLD_START),
- .length = TROUT_CPLD_SIZE,
+ .virtual = DREAM_CPLD_BASE,
+ .pfn = __phys_to_pfn(DREAM_CPLD_START),
+ .length = DREAM_CPLD_SIZE,
.type = MT_DEVICE_NONSHARED
}
};
@@ -76,7 +95,7 @@ static void __init dream_map_io(void)

#ifdef CONFIG_MSM_DEBUG_UART3
/* route UART3 to the "H2W" extended usb connector */
- writeb(0x80, TROUT_CPLD_BASE + 0x00);
+ writeb(0x80, DREAM_CPLD_BASE + 0x00);
#endif

msm_clock_init();
diff --git a/arch/arm/mach-msm/board-dream.h b/arch/arm/mach-msm/board-dream.h
index 4f345a5..aab1faf 100644
--- a/arch/arm/mach-msm/board-dream.h
+++ b/arch/arm/mach-msm/board-dream.h
@@ -1,5 +1,153 @@

-#define TROUT_CPLD_BASE 0xE8100000
-#define TROUT_CPLD_START 0x98000000
-#define TROUT_CPLD_SIZE SZ_4K
+#define MSM_SMI_BASE 0x00000000
+#define MSM_SMI_SIZE 0x00800000

+#define MSM_EBI_BASE 0x10000000
+#define MSM_EBI_SIZE 0x06e00000
+
+#define MSM_PMEM_GPU0_BASE 0x00000000
+#define MSM_PMEM_GPU0_SIZE 0x00700000
+
+#define MSM_PMEM_MDP_BASE 0x02000000
+#define MSM_PMEM_MDP_SIZE 0x00800000
+
+#define MSM_PMEM_ADSP_BASE 0x02800000
+#define MSM_PMEM_ADSP_SIZE 0x00800000
+
+#define MSM_PMEM_CAMERA_BASE 0x03000000
+#define MSM_PMEM_CAMERA_SIZE 0x00800000
+
+#define MSM_FB_BASE 0x03800000
+#define MSM_FB_SIZE 0x00100000
+
+#define MSM_LINUX_BASE MSM_EBI_BASE
+#define MSM_LINUX_SIZE 0x06500000
+
+#define MSM_PMEM_GPU1_SIZE 0x800000
+#define MSM_PMEM_GPU1_BASE (MSM_RAM_CONSOLE_BASE - MSM_PMEM_GPU1_SIZE)
+
+#define MSM_RAM_CONSOLE_BASE (MSM_EBI_BASE + 0x6d00000)
+#define MSM_RAM_CONSOLE_SIZE (128 * SZ_1K)
+
+#if (MSM_FB_BASE + MSM_FB_SIZE) >= (MSM_PMEM_GPU1_BASE)
+#error invalid memory map
+#endif
+
+#define DECLARE_MSM_IOMAP
+#include <mach/msm_iomap.h>
+
+#define DREAM_4_BALL_UP_0 1
+#define DREAM_4_BALL_LEFT_0 18
+#define DREAM_4_BALL_DOWN_0 57
+#define DREAM_4_BALL_RIGHT_0 91
+
+#define DREAM_5_BALL_UP_0 94
+#define DREAM_5_BALL_LEFT_0 18
+#define DREAM_5_BALL_DOWN_0 90
+#define DREAM_5_BALL_RIGHT_0 19
+
+#define DREAM_POWER_KEY 20
+
+#define DREAM_4_TP_LS_EN 19
+#define DREAM_5_TP_LS_EN 1
+
+#define DREAM_CPLD_BASE 0xE8100000
+#define DREAM_CPLD_START 0x98000000
+#define DREAM_CPLD_SIZE SZ_4K
+
+#define DREAM_GPIO_CABLE_IN1 (83)
+#define DREAM_GPIO_CABLE_IN2 (49)
+
+#define DREAM_GPIO_START (128)
+
+#define DREAM_GPIO_INT_MASK0_REG (0x0c)
+#define DREAM_GPIO_INT_STAT0_REG (0x0e)
+#define DREAM_GPIO_INT_MASK1_REG (0x14)
+#define DREAM_GPIO_INT_STAT1_REG (0x10)
+
+#define DREAM_GPIO_HAPTIC_PWM (28)
+#define DREAM_GPIO_PS_HOLD (25)
+
+#define DREAM_GPIO_MISC2_BASE (DREAM_GPIO_START + 0x00)
+#define DREAM_GPIO_MISC3_BASE (DREAM_GPIO_START + 0x08)
+#define DREAM_GPIO_MISC4_BASE (DREAM_GPIO_START + 0x10)
+#define DREAM_GPIO_MISC5_BASE (DREAM_GPIO_START + 0x18)
+#define DREAM_GPIO_INT2_BASE (DREAM_GPIO_START + 0x20)
+#define DREAM_GPIO_MISC1_BASE (DREAM_GPIO_START + 0x28)
+#define DREAM_GPIO_VIRTUAL_BASE (DREAM_GPIO_START + 0x30)
+#define DREAM_GPIO_INT5_BASE (DREAM_GPIO_START + 0x48)
+
+#define DREAM_GPIO_CHARGER_EN (DREAM_GPIO_MISC2_BASE + 0)
+#define DREAM_GPIO_ISET (DREAM_GPIO_MISC2_BASE + 1)
+#define DREAM_GPIO_H2W_DAT_DIR (DREAM_GPIO_MISC2_BASE + 2)
+#define DREAM_GPIO_H2W_CLK_DIR (DREAM_GPIO_MISC2_BASE + 3)
+#define DREAM_GPIO_H2W_DAT_GPO (DREAM_GPIO_MISC2_BASE + 4)
+#define DREAM_GPIO_H2W_CLK_GPO (DREAM_GPIO_MISC2_BASE + 5)
+#define DREAM_GPIO_H2W_SEL0 (DREAM_GPIO_MISC2_BASE + 6)
+#define DREAM_GPIO_H2W_SEL1 (DREAM_GPIO_MISC2_BASE + 7)
+
+#define DREAM_GPIO_SPOTLIGHT_EN (DREAM_GPIO_MISC3_BASE + 0)
+#define DREAM_GPIO_FLASH_EN (DREAM_GPIO_MISC3_BASE + 1)
+#define DREAM_GPIO_I2C_PULL (DREAM_GPIO_MISC3_BASE + 2)
+#define DREAM_GPIO_TP_I2C_PULL (DREAM_GPIO_MISC3_BASE + 3)
+#define DREAM_GPIO_TP_EN (DREAM_GPIO_MISC3_BASE + 4)
+#define DREAM_GPIO_JOG_EN (DREAM_GPIO_MISC3_BASE + 5)
+#define DREAM_GPIO_UI_LED_EN (DREAM_GPIO_MISC3_BASE + 6)
+#define DREAM_GPIO_QTKEY_LED_EN (DREAM_GPIO_MISC3_BASE + 7)
+
+#define DREAM_GPIO_VCM_PWDN (DREAM_GPIO_MISC4_BASE + 0)
+#define DREAM_GPIO_USB_H2W_SW (DREAM_GPIO_MISC4_BASE + 1)
+#define DREAM_GPIO_COMPASS_RST_N (DREAM_GPIO_MISC4_BASE + 2)
+#define DREAM_GPIO_HAPTIC_EN_UP (DREAM_GPIO_MISC4_BASE + 3)
+#define DREAM_GPIO_HAPTIC_EN_MAIN (DREAM_GPIO_MISC4_BASE + 4)
+#define DREAM_GPIO_USB_PHY_RST_N (DREAM_GPIO_MISC4_BASE + 5)
+#define DREAM_GPIO_WIFI_PA_RESETX (DREAM_GPIO_MISC4_BASE + 6)
+#define DREAM_GPIO_WIFI_EN (DREAM_GPIO_MISC4_BASE + 7)
+
+#define DREAM_GPIO_BT_32K_EN (DREAM_GPIO_MISC5_BASE + 0)
+#define DREAM_GPIO_MAC_32K_EN (DREAM_GPIO_MISC5_BASE + 1)
+#define DREAM_GPIO_MDDI_32K_EN (DREAM_GPIO_MISC5_BASE + 2)
+#define DREAM_GPIO_COMPASS_32K_EN (DREAM_GPIO_MISC5_BASE + 3)
+
+#define DREAM_GPIO_NAVI_ACT_N (DREAM_GPIO_INT2_BASE + 0)
+#define DREAM_GPIO_COMPASS_IRQ (DREAM_GPIO_INT2_BASE + 1)
+#define DREAM_GPIO_SLIDING_DET (DREAM_GPIO_INT2_BASE + 2)
+#define DREAM_GPIO_AUD_HSMIC_DET_N (DREAM_GPIO_INT2_BASE + 3)
+#define DREAM_GPIO_SD_DOOR_N (DREAM_GPIO_INT2_BASE + 4)
+#define DREAM_GPIO_CAM_BTN_STEP1_N (DREAM_GPIO_INT2_BASE + 5)
+#define DREAM_GPIO_CAM_BTN_STEP2_N (DREAM_GPIO_INT2_BASE + 6)
+#define DREAM_GPIO_TP_ATT_N (DREAM_GPIO_INT2_BASE + 7)
+#define DREAM_GPIO_BANK0_FIRST_INT_SOURCE (DREAM_GPIO_NAVI_ACT_N)
+#define DREAM_GPIO_BANK0_LAST_INT_SOURCE (DREAM_GPIO_TP_ATT_N)
+
+#define DREAM_GPIO_H2W_DAT_GPI (DREAM_GPIO_MISC1_BASE + 0)
+#define DREAM_GPIO_H2W_CLK_GPI (DREAM_GPIO_MISC1_BASE + 1)
+#define DREAM_GPIO_CPLD128_VER_0 (DREAM_GPIO_MISC1_BASE + 4)
+#define DREAM_GPIO_CPLD128_VER_1 (DREAM_GPIO_MISC1_BASE + 5)
+#define DREAM_GPIO_CPLD128_VER_2 (DREAM_GPIO_MISC1_BASE + 6)
+#define DREAM_GPIO_CPLD128_VER_3 (DREAM_GPIO_MISC1_BASE + 7)
+
+#define DREAM_GPIO_SDMC_CD_N (DREAM_GPIO_VIRTUAL_BASE + 0)
+#define DREAM_GPIO_END (DREAM_GPIO_SDMC_CD_N)
+#define DREAM_GPIO_BANK1_FIRST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
+#define DREAM_GPIO_BANK1_LAST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
+
+#define DREAM_GPIO_VIRTUAL_TO_REAL_OFFSET \
+ (DREAM_GPIO_INT5_BASE - DREAM_GPIO_VIRTUAL_BASE)
+
+#define DREAM_INT_START (NR_MSM_IRQS + NR_GPIO_IRQS)
+#define DREAM_INT_BANK0_COUNT (8)
+#define DREAM_INT_BANK1_START (DREAM_INT_START + DREAM_INT_BANK0_COUNT)
+#define DREAM_INT_BANK1_COUNT (1)
+#define DREAM_INT_END (DREAM_INT_START + DREAM_INT_BANK0_COUNT + \
+ DREAM_INT_BANK1_COUNT - 1)
+#define DREAM_GPIO_TO_INT(n) (((n) <= DREAM_GPIO_BANK0_LAST_INT_SOURCE) ? \
+ (DREAM_INT_START - DREAM_GPIO_BANK0_FIRST_INT_SOURCE + (n)) : \
+ (DREAM_INT_BANK1_START - DREAM_GPIO_BANK1_FIRST_INT_SOURCE + (n)))
+
+#define DREAM_INT_TO_BANK(n) ((n - DREAM_INT_START) / DREAM_INT_BANK0_COUNT)
+#define DREAM_INT_TO_MASK(n) (1U << ((n - DREAM_INT_START) & 7))
+#define DREAM_BANK_TO_MASK_REG(bank) \
+ (bank ? DREAM_GPIO_INT_MASK1_REG : DREAM_GPIO_INT_MASK0_REG)
+#define DREAM_BANK_TO_STAT_REG(bank) \
+ (bank ? DREAM_GPIO_INT_STAT1_REG : DREAM_GPIO_INT_STAT0_REG)
diff --git a/arch/arm/mach-msm/generic_gpio.c b/arch/arm/mach-msm/generic_gpio.c
new file mode 100644
index 0000000..8ee7bd5
--- /dev/null
+++ b/arch/arm/mach-msm/generic_gpio.c
@@ -0,0 +1,282 @@
+/* arch/arm/mach-msm/generic_gpio.c
+ *
+ * Copyright (C) 2007 Google, Inc.
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that 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/kernel.h>
+#include <linux/module.h>
+#include <linux/errno.h>
+#include <linux/slab.h>
+#include <linux/spinlock.h>
+#include <asm/gpio.h>
+#include "gpio_chip.h"
+
+#define GPIO_NUM_TO_CHIP_INDEX(gpio) ((gpio)>>5)
+
+struct gpio_state {
+ unsigned long flags;
+ int refcount;
+};
+
+static DEFINE_SPINLOCK(gpio_chips_lock);
+static LIST_HEAD(gpio_chip_list);
+static struct gpio_chip **gpio_chip_array;
+static unsigned long gpio_chip_array_size;
+
+int register_gpio_chip(struct gpio_chip *new_gpio_chip)
+{
+ int err = 0;
+ struct gpio_chip *gpio_chip;
+ int i;
+ unsigned long irq_flags;
+ /* Start/end indexes into chip array */
+ unsigned int start, end;
+ int size = (new_gpio_chip->end + 1 - new_gpio_chip->start) *
+ sizeof(new_gpio_chip->state[0]);
+
+ new_gpio_chip->state = kzalloc(size, GFP_KERNEL);
+ if (new_gpio_chip->state == NULL) {
+ printk(KERN_ERR "register_gpio_chip: failed to allocate state\n");
+ return -ENOMEM;
+ }
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ start = GPIO_NUM_TO_CHIP_INDEX(new_gpio_chip->start);
+ end = GPIO_NUM_TO_CHIP_INDEX(new_gpio_chip->end);
+
+ if (end >= gpio_chip_array_size) {
+ /* New gpio chip array */
+ struct gpio_chip **new_array;
+ /* Size of gpio chip array */
+ unsigned long array_size = end + 1;
+
+ new_array = kmalloc(array_size * sizeof(new_array[0]), GFP_ATOMIC);
+ if (!new_array) {
+ printk(KERN_ERR "register_gpio_chip: failed to allocate array\n");
+ err = -ENOMEM;
+ goto failed;
+ }
+ for (i = 0; i < gpio_chip_array_size; i++)
+ new_array[i] = gpio_chip_array[i];
+ for (i = gpio_chip_array_size; i < array_size; i++)
+ new_array[i] = NULL;
+ gpio_chip_array = new_array;
+ gpio_chip_array_size = array_size;
+ }
+
+ list_for_each_entry(gpio_chip, &gpio_chip_list, list) {
+ if (gpio_chip->start > new_gpio_chip->end) {
+ list_add_tail(&new_gpio_chip->list, &gpio_chip->list);
+ goto added;
+ }
+ if (gpio_chip->end >= new_gpio_chip->start) {
+ printk(KERN_ERR "register_gpio_source %u-%u overlaps with %u-%u\n",
+ new_gpio_chip->start, new_gpio_chip->end,
+ gpio_chip->start, gpio_chip->end);
+ err = -EBUSY;
+ goto failed;
+ }
+ }
+
+ list_add_tail(&new_gpio_chip->list, &gpio_chip_list);
+added:
+ for (i = start; i <= end; i++) {
+ if ((!gpio_chip_array[i]) || gpio_chip_array[i]->start > new_gpio_chip->start)
+ gpio_chip_array[i] = new_gpio_chip;
+ }
+failed:
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ if (err)
+ kfree(new_gpio_chip->state);
+ return err;
+}
+
+static struct gpio_chip *get_gpio_chip_locked(unsigned int gpio)
+{
+ unsigned long i;
+ struct gpio_chip *chip;
+
+ i = GPIO_NUM_TO_CHIP_INDEX(gpio);
+ if (i >= gpio_chip_array_size)
+ return NULL;
+ chip = gpio_chip_array[i];
+ if (chip == NULL)
+ return NULL;
+ list_for_each_entry_from(chip, &gpio_chip_list, list) {
+ if (gpio < chip->start)
+ return NULL;
+ if (gpio <= chip->end)
+ return chip;
+ }
+ return NULL;
+}
+
+static int request_gpio(unsigned int gpio, unsigned long flags)
+{
+ int err = 0;
+ struct gpio_chip *chip;
+ unsigned long irq_flags;
+ unsigned long chip_index;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip == NULL) {
+ err = -EINVAL;
+ goto err;
+ }
+ chip_index = gpio - chip->start;
+ if (chip->state[chip_index].refcount == 0) {
+ chip->configure(chip, gpio, flags);
+ chip->state[chip_index].flags = flags;
+ chip->state[chip_index].refcount++;
+ } else if ((flags & IRQF_SHARED) && (chip->state[chip_index].flags & IRQF_SHARED))
+ chip->state[chip_index].refcount++;
+ else
+ err = -EBUSY;
+err:
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ return err;
+}
+
+int gpio_request(unsigned gpio, const char *label)
+{
+ return request_gpio(gpio, 0);
+}
+EXPORT_SYMBOL(gpio_request);
+
+void gpio_free(unsigned gpio)
+{
+ struct gpio_chip *chip;
+ unsigned long irq_flags;
+ unsigned long chip_index;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip) {
+ chip_index = gpio - chip->start;
+ chip->state[chip_index].refcount--;
+ }
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+}
+EXPORT_SYMBOL(gpio_free);
+
+static int gpio_get_irq_num(unsigned int gpio, unsigned int *irqp, unsigned long *irqnumflagsp)
+{
+ int ret = -ENOTSUPP;
+ struct gpio_chip *chip;
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip && chip->get_irq_num)
+ ret = chip->get_irq_num(chip, gpio, irqp, irqnumflagsp);
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ return ret;
+}
+
+int gpio_to_irq(unsigned gpio)
+{
+ int ret, irq;
+ ret = gpio_get_irq_num(gpio, &irq, NULL);
+ if (ret)
+ return ret;
+ return irq;
+}
+EXPORT_SYMBOL(gpio_to_irq);
+
+int gpio_configure(unsigned int gpio, unsigned long flags)
+{
+ int ret = -ENOTSUPP;
+ struct gpio_chip *chip;
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip)
+ ret = chip->configure(chip, gpio, flags);
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ return ret;
+}
+EXPORT_SYMBOL(gpio_configure);
+
+int gpio_direction_input(unsigned gpio)
+{
+ return gpio_configure(gpio, GPIOF_INPUT);
+}
+EXPORT_SYMBOL(gpio_direction_input);
+
+int gpio_direction_output(unsigned gpio, int value)
+{
+ gpio_set_value(gpio, value);
+ return gpio_configure(gpio, GPIOF_DRIVE_OUTPUT);
+}
+EXPORT_SYMBOL(gpio_direction_output);
+
+int gpio_get_value(unsigned gpio)
+{
+ int ret = -ENOTSUPP;
+ struct gpio_chip *chip;
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip && chip->read)
+ ret = chip->read(chip, gpio);
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ return ret;
+}
+EXPORT_SYMBOL(gpio_get_value);
+
+void gpio_set_value(unsigned gpio, int on)
+{
+ int ret = -ENOTSUPP;
+ struct gpio_chip *chip;
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip && chip->write)
+ ret = chip->write(chip, gpio, on);
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+}
+EXPORT_SYMBOL(gpio_set_value);
+
+int gpio_read_detect_status(unsigned int gpio)
+{
+ int ret = -ENOTSUPP;
+ struct gpio_chip *chip;
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip && chip->read_detect_status)
+ ret = chip->read_detect_status(chip, gpio);
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ return ret;
+}
+EXPORT_SYMBOL(gpio_read_detect_status);
+
+int gpio_clear_detect_status(unsigned int gpio)
+{
+ int ret = -ENOTSUPP;
+ struct gpio_chip *chip;
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip && chip->clear_detect_status)
+ ret = chip->clear_detect_status(chip, gpio);
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ return ret;
+}
+EXPORT_SYMBOL(gpio_clear_detect_status);
diff --git a/arch/arm/mach-msm/gpio_chip.h b/arch/arm/mach-msm/gpio_chip.h
new file mode 100644
index 0000000..ee4eddc
--- /dev/null
+++ b/arch/arm/mach-msm/gpio_chip.h
@@ -0,0 +1,50 @@
+/* arch/arm/mach-msm/gpio_chip.h
+ *
+ * Copyright (C) 2007 Google, Inc.
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that 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.
+ *
+ */
+
+#ifndef _LINUX_GPIO_CHIP_H
+#define _LINUX_GPIO_CHIP_H
+
+#include <linux/list.h>
+
+struct gpio_chip {
+ struct list_head list;
+ struct gpio_state *state;
+
+ unsigned int start;
+ unsigned int end;
+
+ int (*configure)(struct gpio_chip *chip, unsigned int gpio, unsigned long flags);
+ int (*get_irq_num)(struct gpio_chip *chip, unsigned int gpio, unsigned int *irqp, unsigned long *irqnumflagsp);
+ int (*read)(struct gpio_chip *chip, unsigned int gpio);
+ int (*write)(struct gpio_chip *chip, unsigned int gpio, unsigned on);
+ int (*read_detect_status)(struct gpio_chip *chip, unsigned int gpio);
+ int (*clear_detect_status)(struct gpio_chip *chip, unsigned int gpio);
+};
+
+int register_gpio_chip(struct gpio_chip *gpio_chip);
+
+/* extended gpio api */
+
+#define GPIOF_IRQF_MASK 0x0000ffff /* use to specify edge detection without */
+#define GPIOF_IRQF_TRIGGER_NONE 0x00010000 /* IRQF_TRIGGER_NONE is 0 which also means "as already configured" */
+#define GPIOF_INPUT 0x00020000
+#define GPIOF_DRIVE_OUTPUT 0x00040000
+#define GPIOF_OUTPUT_LOW 0x00080000
+#define GPIOF_OUTPUT_HIGH 0x00100000
+
+#define GPIOIRQF_SHARED 0x00000001 /* the irq line is shared with other inputs */
+
+
+#endif
diff --git a/arch/arm/mach-msm/include/mach/gpio.h b/arch/arm/mach-msm/include/mach/gpio.h
new file mode 100644
index 0000000..92ce18d
--- /dev/null
+++ b/arch/arm/mach-msm/include/mach/gpio.h
@@ -0,0 +1,36 @@
+/* linux/include/asm-arm/arch-msm/gpio.h
+ *
+ * Copyright (C) 2007 Google, Inc.
+ * Author: Mike Lockwood <[email protected]>
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that 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.
+ *
+ */
+
+#ifndef __ASM_ARCH_MSM_GPIO_H
+#define __ASM_ARCH_MSM_GPIO_H
+
+#include <linux/interrupt.h>
+
+int gpio_request(unsigned gpio, const char *label);
+void gpio_free(unsigned gpio);
+int gpio_direction_input(unsigned gpio);
+int gpio_direction_output(unsigned gpio, int value);
+int gpio_get_value(unsigned gpio);
+void gpio_set_value(unsigned gpio, int value);
+int gpio_to_irq(unsigned gpio);
+
+#include <asm-generic/gpio.h>
+
+extern int gpio_configure(unsigned int gpio, unsigned long flags);
+extern int gpio_read_detect_status(unsigned int gpio);
+extern int gpio_clear_detect_status(unsigned int gpio);
+
+#endif


--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-08 21:52:38

by Ryan Mallon

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

Pavel Machek wrote:
> Hi!
>
>>> +#undef MODULE_PARAM_PREFIX
>>> +#define MODULE_PARAM_PREFIX "board_dream."
>> This looks a bit dodgy. Is this
>> (http://lkml.indiana.edu/hypermail/linux/kernel/0903.0/02768.html) the
>> preferred way?
>
> I don't think that would help that much here....

Okay, but what is the reason for overriding MODULE_PARAM_PREFIX? Maybe a
comment explaining?

>>> +static void update_pwrsink(unsigned gpio, unsigned on)
>>> +{
>>> + switch(gpio) {
>>> + case DREAM_GPIO_UI_LED_EN:
>>> + break;
>>> + case DREAM_GPIO_QTKEY_LED_EN:
>>> + break;
>>> + }
>>> +}
>> What is this function for?
>
> Power accounting... should be removed. Fixed.
>
>>> +static void dream_gpio_irq_ack(unsigned int irq)
>>> +{
>>> + int bank = DREAM_INT_TO_BANK(irq);
>>> + uint8_t mask = DREAM_INT_TO_MASK(irq);
>>> + int reg = DREAM_BANK_TO_STAT_REG(bank);
>>> + /*printk(KERN_INFO "dream_gpio_irq_ack irq %d\n", irq);*/
>> pr_debug, or just remove it?
>
> Remove.
>
>>> + desc->chip->ack(irq);
>>> +}
>> Some blank lines here and there would make this more readable. All your
>> code is wedged together :-).
>
> Well, added some blank lines; not sure it is improvement.

This function was just an example, the patch lacked blank lines in
general. Squashed up code is hard to read.

>>> +#define DREAM_INT_TO_BANK(n) ((n - DREAM_INT_START) / DREAM_INT_BANK0_COUNT)
>>> +#define DREAM_INT_TO_MASK(n) (1U << ((n - DREAM_INT_START) & 7))
>>> +#define DREAM_BANK_TO_MASK_REG(bank) \
>>> + (bank ? DREAM_GPIO_INT_MASK1_REG : DREAM_GPIO_INT_MASK0_REG)
>>> +#define DREAM_BANK_TO_STAT_REG(bank) \
>>> + (bank ? DREAM_GPIO_INT_STAT1_REG : DREAM_GPIO_INT_STAT0_REG)
>> Are these needed outside of the gpiolib code? If not, they should be
>> moved there. I also think they should have lower case names since they
>> act like a function, and make the code where they are used nicer to
>> read.
>
> I guess these logically belong here.
>
> No, macros are macros, that means upcase.

container_of, min, swap, etc are macros too. It is easier to read this
if they are lower case because they are typically used for initialising
variables, ie:

int bank = dream_int_to_bank(irq);

Is easier (IMHO) to read than:

int bank = DREAM_INT_TO_BANK(irq);


>> Thats big, hard to read, has about 3 blank lines total and no comments.
>
> I tried to improve it, but it needs more. Here are my cleanups.
> Pavel

Looks better overall.

> diff --git a/arch/arm/mach-msm/board-dream.c b/arch/arm/mach-msm/board-dream.c
> index 4758957..3e8e54a 100644
> --- a/arch/arm/mach-msm/board-dream.c
> +++ b/arch/arm/mach-msm/board-dream.c
> @@ -59,6 +59,23 @@ static void __init dream_fixup(struct machine_desc *desc, struct tag *tags,
>
> static void __init dream_init(void)
> {
> + gpio_set_value(DREAM_GPIO_UI_LED_EN, 1);
> + mdelay(300);
> + gpio_set_value(DREAM_GPIO_UI_LED_EN, 0);
> + mdelay(300);
> + gpio_set_value(DREAM_GPIO_UI_LED_EN, 1);
> + mdelay(300);
> + gpio_set_value(DREAM_GPIO_UI_LED_EN, 0);
> + mdelay(300);
> + gpio_set_value(DREAM_GPIO_UI_LED_EN, 1);
> + mdelay(300);
> + gpio_set_value(DREAM_GPIO_UI_LED_EN, 0);
> + mdelay(300);
> + gpio_set_value(DREAM_GPIO_UI_LED_EN, 1);
> + mdelay(300);
> + gpio_set_value(DREAM_GPIO_UI_LED_EN, 0);
> + mdelay(300);
> +

Indentation looks screwy here. Also, is this meant to blink the leds?
There is a 2.4 second hard delay here, which is horrible.

~Ryan

--
Bluewater Systems Ltd - ARM Technology Solution Centre

Ryan Mallon 5 Amuri Park, 404 Barbadoes St
[email protected] PO Box 13 889, Christchurch 8013
http://www.bluewatersys.com New Zealand
Phone: +64 3 3779127 Freecall: Australia 1800 148 751
Fax: +64 3 3779135 USA 1800 261 2934

2009-12-08 21:55:59

by Arve Hjønnevåg

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Tue, Dec 8, 2009 at 1:37 PM, Pavel Machek <[email protected]> wrote:
> Hi!
>
>> > +#undef MODULE_PARAM_PREFIX
>> > +#define MODULE_PARAM_PREFIX "board_dream."
>>
>> This looks a bit dodgy. Is this
>> (http://lkml.indiana.edu/hypermail/linux/kernel/0903.0/02768.html) the
>> preferred way?
>
> I don't think that would help that much here....

That should work, but you have to use board_trout, not board_dream.
Many of these parameters passed on the kernel command-line by the
bootloader which uses board_trout. Others are used by userspace which
also expects to find them under board_trout.

--
Arve Hj?nnev?g

2009-12-08 22:03:29

by Joe Perches

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Tue, 2009-12-08 at 22:46 +0100, Pavel Machek wrote:
> Add GPIO support for HTC Dream.

Hi Pavel. Thanks for this.

Maybe it'd be nicer to use pr_<level> and add
#define pr_fmt(fmt) KBUILD_MODNAME ":%s: " fmt, __func__
?

> +++ b/arch/arm/mach-msm/board-dream-gpio.c
> +static int dream_gpio_write(struct gpio_chip *chip, unsigned n, unsigned on)
[]
> + printk(KERN_ERR "dream_gpio_write called on input %d\n", n);
pr_err("called on input %d\n", n);
[]
> +static void dream_gpio_irq_handler(unsigned int irq, struct irq_desc *desc)
[]
> + printk(KERN_ERR "dream_gpio_irq_handler: got masked "
pr_err("got masked interrupt: %d:%02x\n"
> +++ b/arch/arm/mach-msm/generic_gpio.c
[]
> +int register_gpio_chip(struct gpio_chip *new_gpio_chip)
[]
> + printk(KERN_ERR "register_gpio_chip: failed to allocate state\n");
pr_err("failed to allocate state\n");
> + printk(KERN_ERR "register_gpio_chip: failed to allocate array\n");
pr_err("failed to allocate array\n");
[]
> + printk(KERN_ERR "register_gpio_source %u-%u overlaps with %u-%u\n",
Wrong function name?
pr_err("%u-%u overlaps with %u-%u\n",

2009-12-08 22:10:24

by Ryan Mallon

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

Pavel Machek wrote:
> Add GPIO support for HTC Dream.
>
> Signed-off-by: Pavel Machek <[email protected]>
>
> +int register_gpio_chip(struct gpio_chip *new_gpio_chip)
> +{
> + int err = 0;
> + struct gpio_chip *gpio_chip;
> + int i;
> + unsigned long irq_flags;
> + /* Start/end indexes into chip array */
> + unsigned int start, end;
> + int size = (new_gpio_chip->end + 1 - new_gpio_chip->start) *
> + sizeof(new_gpio_chip->state[0]);
> +
> + new_gpio_chip->state = kzalloc(size, GFP_KERNEL);
> + if (new_gpio_chip->state == NULL) {
> + printk(KERN_ERR "register_gpio_chip: failed to allocate state\n");
> + return -ENOMEM;
> + }
> +
> + spin_lock_irqsave(&gpio_chips_lock, irq_flags);
> + start = GPIO_NUM_TO_CHIP_INDEX(new_gpio_chip->start);
> + end = GPIO_NUM_TO_CHIP_INDEX(new_gpio_chip->end);
> +
> + if (end >= gpio_chip_array_size) {
> + /* New gpio chip array */
> + struct gpio_chip **new_array;
> + /* Size of gpio chip array */
> + unsigned long array_size = end + 1;
> +
> + new_array = kmalloc(array_size * sizeof(new_array[0]), GFP_ATOMIC);
> + if (!new_array) {
> + printk(KERN_ERR "register_gpio_chip: failed to allocate array\n");
> + err = -ENOMEM;
> + goto failed;
> + }
> + for (i = 0; i < gpio_chip_array_size; i++)
> + new_array[i] = gpio_chip_array[i];
> + for (i = gpio_chip_array_size; i < array_size; i++)
> + new_array[i] = NULL;
> + gpio_chip_array = new_array;
> + gpio_chip_array_size = array_size;
> + }
> +
> + list_for_each_entry(gpio_chip, &gpio_chip_list, list) {
> + if (gpio_chip->start > new_gpio_chip->end) {
> + list_add_tail(&new_gpio_chip->list, &gpio_chip->list);
> + goto added;
> + }
> + if (gpio_chip->end >= new_gpio_chip->start) {
> + printk(KERN_ERR "register_gpio_source %u-%u overlaps with %u-%u\n",
> + new_gpio_chip->start, new_gpio_chip->end,
> + gpio_chip->start, gpio_chip->end);
> + err = -EBUSY;
> + goto failed;
> + }
> + }
> +
> + list_add_tail(&new_gpio_chip->list, &gpio_chip_list);
> +added:
> + for (i = start; i <= end; i++) {
> + if ((!gpio_chip_array[i]) || gpio_chip_array[i]->start > new_gpio_chip->start)
> + gpio_chip_array[i] = new_gpio_chip;
> + }
> +failed:
> + spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
> + if (err)
> + kfree(new_gpio_chip->state);
> + return err;
> +}

This is still really screwy. Why are you creating your own version of
struct gpio_chip in addition to the one in include/asm-generic/gpio.h
(which you also appear to include in some places). It makes the code
extremely confusing. Other architectures use wrapper structures. Can you
have something like this instead:

struct dream_gpio_chip {
struct gpio_chip chip;

/* Dream specific bits */
};

The name of this function also needs to be changed to something less
generic since it is being exported globally.

I also think this function is doing way to much work for what it is.
Does it really need to be this complicated?

~Ryan

--
Bluewater Systems Ltd - ARM Technology Solution Centre

Ryan Mallon 5 Amuri Park, 404 Barbadoes St
[email protected] PO Box 13 889, Christchurch 8013
http://www.bluewatersys.com New Zealand
Phone: +64 3 3779127 Freecall: Australia 1800 148 751
Fax: +64 3 3779135 USA 1800 261 2934

2009-12-08 22:46:02

by Russell King - ARM Linux

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Tue, Dec 08, 2009 at 11:28:43AM +0100, Pavel Machek wrote:
> Add GPIO support for HTC Dream.
>
> Signed-off-by: Pavel Machek <[email protected]>
>
> diff --git a/arch/arm/mach-msm/Kconfig b/arch/arm/mach-msm/Kconfig
> index f780086..774c50e 100644
> --- a/arch/arm/mach-msm/Kconfig
> +++ b/arch/arm/mach-msm/Kconfig
> @@ -40,4 +40,8 @@ config MACH_TROUT
> help
> Support for the HTC Dream, T-Mobile G1, Android ADP1 devices.
>
> +config GENERIC_GPIO
> + bool
> + default y

Please arrange for this to be handled just like every other ARM
platform via a 'select' statement - eg:

config ARCH_AT91
bool "Atmel AT91"
select GENERIC_GPIO
select ARCH_REQUIRE_GPIOLIB
select HAVE_CLK

It is not nice to have multiple definitions of the same symbol scattered
throughout the Kconfig files.

> +
> endif
> diff --git a/arch/arm/mach-msm/Makefile b/arch/arm/mach-msm/Makefile
> index 91e6f5c..4c2567e 100644
> --- a/arch/arm/mach-msm/Makefile
> +++ b/arch/arm/mach-msm/Makefile
> @@ -6,4 +6,4 @@ obj-y += clock.o clock-7x01a.o
>
> obj-$(CONFIG_MACH_HALIBUT) += board-halibut.o
>
> -obj-$(CONFIG_MACH_TROUT) += board-dream.o
> +obj-$(CONFIG_MACH_TROUT) += board-dream.o board-dream-gpio.o generic_gpio.o
> diff --git a/arch/arm/mach-msm/board-dream-gpio.c b/arch/arm/mach-msm/board-dream-gpio.c
> new file mode 100644
> index 0000000..1b23a84
> --- /dev/null
> +++ b/arch/arm/mach-msm/board-dream-gpio.c
> @@ -0,0 +1,301 @@
> +/* arch/arm/mach-msm/board-dream-gpio.c
> + *
> + * Copyright (C) 2008 Google, Inc.
> + *
> + * This software is licensed under the terms of the GNU General Public
> + * License version 2, as published by the Free Software Foundation, and
> + * may be copied, distributed, and modified under those terms.
> + *
> + * This program is distributed in the hope that 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/kernel.h>
> +#include <linux/errno.h>
> +#include <linux/irq.h>
> +#include <linux/pm.h>
> +#include <linux/sysdev.h>
> +#include <linux/io.h>
> +
> +#include <asm/gpio.h>

linux/gpio.h is preferred over asm/gpio.h

> diff --git a/arch/arm/mach-msm/board-dream.c b/arch/arm/mach-msm/board-dream.c
> index d238e2c..4758957 100644
> --- a/arch/arm/mach-msm/board-dream.c
> +++ b/arch/arm/mach-msm/board-dream.c
> @@ -18,11 +18,13 @@
> #include <linux/kernel.h>
> #include <linux/init.h>
> #include <linux/platform_device.h>
> +#include <linux/delay.h>
>
> #include <asm/mach-types.h>
> #include <asm/mach/arch.h>
> #include <asm/mach/map.h>
> #include <asm/setup.h>
> +#include <asm/gpio.h>

ditto.

> diff --git a/arch/arm/mach-msm/generic_gpio.c b/arch/arm/mach-msm/generic_gpio.c
> new file mode 100644
> index 0000000..fe24d38
> --- /dev/null
> +++ b/arch/arm/mach-msm/generic_gpio.c
> @@ -0,0 +1,274 @@
> +/* arch/arm/mach-msm/generic_gpio.c
> + *
> + * Copyright (C) 2007 Google, Inc.
> + *
> + * This software is licensed under the terms of the GNU General Public
> + * License version 2, as published by the Free Software Foundation, and
> + * may be copied, distributed, and modified under those terms.
> + *
> + * This program is distributed in the hope that 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/kernel.h>
> +#include <linux/module.h>
> +#include <linux/errno.h>
> +#include <linux/slab.h>
> +#include <linux/spinlock.h>
> +#include <asm/gpio.h>

ditto.

2009-12-09 00:39:09

by Arve Hjønnevåg

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Tue, Dec 8, 2009 at 2:45 PM, Russell King - ARM Linux
<[email protected]> wrote:
> On Tue, Dec 08, 2009 at 11:28:43AM +0100, Pavel Machek wrote:
>> Add GPIO support for HTC Dream.
>>
>> Signed-off-by: Pavel Machek <[email protected]>
>>
>> diff --git a/arch/arm/mach-msm/Kconfig b/arch/arm/mach-msm/Kconfig
>> index f780086..774c50e 100644
>> --- a/arch/arm/mach-msm/Kconfig
>> +++ b/arch/arm/mach-msm/Kconfig
>> @@ -40,4 +40,8 @@ config MACH_TROUT
>> ? ? ? help
>> ? ? ? ? Support for the HTC Dream, T-Mobile G1, Android ADP1 devices.
>>
>> +config GENERIC_GPIO
>> + ? ? bool
>> + ? ? default y
>
> Please arrange for this to be handled just like every other ARM
> platform via a 'select' statement - eg:
>
> config ARCH_AT91
> ? ? ? ?bool "Atmel AT91"
> ? ? ? ?select GENERIC_GPIO
> ? ? ? ?select ARCH_REQUIRE_GPIOLIB
> ? ? ? ?select HAVE_CLK
>
> It is not nice to have multiple definitions of the same symbol scattered
> throughout the Kconfig files.
>

Why did this code get pulled into the dream gpio code? The original
change that adds msm gpio support already selects GENERIC_GPIO
(http://android.git.kernel.org/?p=kernel/msm.git;a=commit;h=5ae9f4403530a5782478c35d29753081750c4188).
Since you copied half of the files from that change anyway, it would
be better to just include that change in you patch set.

--
Arve Hj?nnev?g

2009-12-09 11:32:50

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Tue 2009-12-08 13:56:00, Arve Hj?nnev?g wrote:
> On Tue, Dec 8, 2009 at 1:37 PM, Pavel Machek <[email protected]> wrote:
> > Hi!
> >
> >> > +#undef MODULE_PARAM_PREFIX
> >> > +#define MODULE_PARAM_PREFIX "board_dream."
> >>
> >> This looks a bit dodgy. Is this
> >> (http://lkml.indiana.edu/hypermail/linux/kernel/0903.0/02768.html) the
> >> preferred way?
> >
> > I don't think that would help that much here....
>
> That should work, but you have to use board_trout, not board_dream.
> Many of these parameters passed on the kernel command-line by the
> bootloader which uses board_trout. Others are used by userspace which
> also expects to find them under board_trout.

Ok, lets go for board_trout (and a comment). I guess compatibility is
somehow important here.
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-09 11:37:42

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Tue 2009-12-08 16:39:09, Arve Hj?nnev?g wrote:
> On Tue, Dec 8, 2009 at 2:45 PM, Russell King - ARM Linux
> <[email protected]> wrote:
> > On Tue, Dec 08, 2009 at 11:28:43AM +0100, Pavel Machek wrote:
> >> Add GPIO support for HTC Dream.
> >>
> >> Signed-off-by: Pavel Machek <[email protected]>
> >>
> >> diff --git a/arch/arm/mach-msm/Kconfig b/arch/arm/mach-msm/Kconfig
> >> index f780086..774c50e 100644
> >> --- a/arch/arm/mach-msm/Kconfig
> >> +++ b/arch/arm/mach-msm/Kconfig
> >> @@ -40,4 +40,8 @@ config MACH_TROUT
> >> ? ? ? help
> >> ? ? ? ? Support for the HTC Dream, T-Mobile G1, Android ADP1 devices.
> >>
> >> +config GENERIC_GPIO
> >> + ? ? bool
> >> + ? ? default y
> >
> > Please arrange for this to be handled just like every other ARM
> > platform via a 'select' statement - eg:
> >
> > config ARCH_AT91
> > ? ? ? ?bool "Atmel AT91"
> > ? ? ? ?select GENERIC_GPIO
> > ? ? ? ?select ARCH_REQUIRE_GPIOLIB
> > ? ? ? ?select HAVE_CLK
> >
> > It is not nice to have multiple definitions of the same symbol scattered
> > throughout the Kconfig files.
> >
>
> Why did this code get pulled into the dream gpio code? The original
> change that adds msm gpio support already selects GENERIC_GPIO
> (http://android.git.kernel.org/?p=kernel/msm.git;a=commit;h=5ae9f4403530a5782478c35d29753081750c4188).
> Since you copied half of the files from that change anyway, it would
> be better to just include that change in you patch set.

I'm not sure how to do that with git without pulling all the changes
before that one, too :-(.
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-09 11:41:50

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Tue 2009-12-08 22:45:50, Russell King - ARM Linux wrote:
> On Tue, Dec 08, 2009 at 11:28:43AM +0100, Pavel Machek wrote:
> > Add GPIO support for HTC Dream.
> >
> > Signed-off-by: Pavel Machek <[email protected]>
> >
> > diff --git a/arch/arm/mach-msm/Kconfig b/arch/arm/mach-msm/Kconfig
> > index f780086..774c50e 100644
> > --- a/arch/arm/mach-msm/Kconfig
> > +++ b/arch/arm/mach-msm/Kconfig
> > @@ -40,4 +40,8 @@ config MACH_TROUT
> > help
> > Support for the HTC Dream, T-Mobile G1, Android ADP1 devices.
> >
> > +config GENERIC_GPIO
> > + bool
> > + default y
>
> Please arrange for this to be handled just like every other ARM
> platform via a 'select' statement - eg:
>
> config ARCH_AT91
> bool "Atmel AT91"
> select GENERIC_GPIO
> select ARCH_REQUIRE_GPIOLIB
> select HAVE_CLK
>
> It is not nice to have multiple definitions of the same symbol scattered
> throughout the Kconfig files.

Ok, fixed.

> > +#include <linux/kernel.h>
> > +#include <linux/errno.h>
> > +#include <linux/irq.h>
> > +#include <linux/pm.h>
> > +#include <linux/sysdev.h>
> > +#include <linux/io.h>
> > +
> > +#include <asm/gpio.h>
>
> linux/gpio.h is preferred over asm/gpio.h

Ok.

> > +++ b/arch/arm/mach-msm/board-dream.c
> > @@ -18,11 +18,13 @@
> > #include <asm/setup.h>
> > +#include <asm/gpio.h>
>
> ditto.

Ok.

> > +++ b/arch/arm/mach-msm/generic_gpio.c
> > @@ -0,0 +1,274 @@
> > +#include <linux/kernel.h>
> > +#include <linux/module.h>
> > +#include <linux/errno.h>
> > +#include <linux/slab.h>
> > +#include <linux/spinlock.h>
> > +#include <asm/gpio.h>
>
> ditto.

Ok. Incremental patch looks like:

diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig
index 1c4119c..db622a5 100644
--- a/arch/arm/Kconfig
+++ b/arch/arm/Kconfig
@@ -565,6 +565,7 @@ config ARCH_MSM
select CPU_V6
select GENERIC_TIME
select GENERIC_CLOCKEVENTS
+ select GENERIC_GPIO
help
Support for Qualcomm MSM7K based systems. This runs on the ARM11
apps processor of the MSM7K and depends on a shared memory
diff --git a/arch/arm/mach-msm/Kconfig b/arch/arm/mach-msm/Kconfig
index 774c50e..f780086 100644
--- a/arch/arm/mach-msm/Kconfig
+++ b/arch/arm/mach-msm/Kconfig
@@ -40,8 +40,4 @@ config MACH_TROUT
help
Support for the HTC Dream, T-Mobile G1, Android ADP1 devices.

-config GENERIC_GPIO
- bool
- default y
-
endif
diff --git a/arch/arm/mach-msm/board-dream-gpio.c b/arch/arm/mach-msm/board-dream-gpio.c
index 7796254..d9201f9 100644
--- a/arch/arm/mach-msm/board-dream-gpio.c
+++ b/arch/arm/mach-msm/board-dream-gpio.c
@@ -19,15 +19,16 @@
#include <linux/pm.h>
#include <linux/sysdev.h>
#include <linux/io.h>
+#include <linux/gpio.h>

-#include <asm/gpio.h>
#include <asm/mach-types.h>

#include "board-dream.h"
#include "gpio_chip.h"

+/* We want to be compatible with existing bootloaders */
#undef MODULE_PARAM_PREFIX
-#define MODULE_PARAM_PREFIX "board_dream."
+#define MODULE_PARAM_PREFIX "board_trout."

static uint cpld_usb_h2w_sw;
module_param_named(usb_h2w_sw, cpld_usb_h2w_sw, uint, 0);
diff --git a/arch/arm/mach-msm/board-dream.c b/arch/arm/mach-msm/board-dream.c
index 3e8e54a..edefacf 100644
--- a/arch/arm/mach-msm/board-dream.c
+++ b/arch/arm/mach-msm/board-dream.c
@@ -19,12 +19,12 @@
#include <linux/init.h>
#include <linux/platform_device.h>
#include <linux/delay.h>
+#include <linux/gpio.h>

#include <asm/mach-types.h>
#include <asm/mach/arch.h>
#include <asm/mach/map.h>
#include <asm/setup.h>
-#include <asm/gpio.h>

#include <mach/board.h>
#include <mach/hardware.h>
diff --git a/arch/arm/mach-msm/generic_gpio.c b/arch/arm/mach-msm/generic_gpio.c
index 8ee7bd5..5164c77 100644
--- a/arch/arm/mach-msm/generic_gpio.c
+++ b/arch/arm/mach-msm/generic_gpio.c
@@ -18,7 +18,8 @@
#include <linux/errno.h>
#include <linux/slab.h>
#include <linux/spinlock.h>
-#include <asm/gpio.h>
+#include <linux/gpio.h>
+
#include "gpio_chip.h"

#define GPIO_NUM_TO_CHIP_INDEX(gpio) ((gpio)>>5)




--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-09 11:42:39

by Arve Hjønnevåg

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Wed, Dec 9, 2009 at 3:37 AM, Pavel Machek <[email protected]> wrote:
> On Tue 2009-12-08 16:39:09, Arve Hj?nnev?g wrote:
>> On Tue, Dec 8, 2009 at 2:45 PM, Russell King - ARM Linux
>> <[email protected]> wrote:
>> > On Tue, Dec 08, 2009 at 11:28:43AM +0100, Pavel Machek wrote:
>> >> Add GPIO support for HTC Dream.
>> >>
>> >> Signed-off-by: Pavel Machek <[email protected]>
>> >>
>> >> diff --git a/arch/arm/mach-msm/Kconfig b/arch/arm/mach-msm/Kconfig
>> >> index f780086..774c50e 100644
>> >> --- a/arch/arm/mach-msm/Kconfig
>> >> +++ b/arch/arm/mach-msm/Kconfig
>> >> @@ -40,4 +40,8 @@ config MACH_TROUT
>> >> ? ? ? help
>> >> ? ? ? ? Support for the HTC Dream, T-Mobile G1, Android ADP1 devices.
>> >>
>> >> +config GENERIC_GPIO
>> >> + ? ? bool
>> >> + ? ? default y
>> >
>> > Please arrange for this to be handled just like every other ARM
>> > platform via a 'select' statement - eg:
>> >
>> > config ARCH_AT91
>> > ? ? ? ?bool "Atmel AT91"
>> > ? ? ? ?select GENERIC_GPIO
>> > ? ? ? ?select ARCH_REQUIRE_GPIOLIB
>> > ? ? ? ?select HAVE_CLK
>> >
>> > It is not nice to have multiple definitions of the same symbol scattered
>> > throughout the Kconfig files.
>> >
>>
>> Why did this code get pulled into the dream gpio code? The original
>> change that adds msm gpio support already selects GENERIC_GPIO
>> (http://android.git.kernel.org/?p=kernel/msm.git;a=commit;h=5ae9f4403530a5782478c35d29753081750c4188).
>> Since you copied half of the files from that change anyway, it would
>> be better to just include that change in you patch set.
>
> I'm not sure how to do that with git without pulling all the changes
> before that one, too :-(.

git cherry-pick

--
Arve Hj?nnev?g

2009-12-09 11:46:11

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Tue 2009-12-08 14:03:32, Joe Perches wrote:
> On Tue, 2009-12-08 at 22:46 +0100, Pavel Machek wrote:
> > Add GPIO support for HTC Dream.
>
> Hi Pavel. Thanks for this.
>
> Maybe it'd be nicer to use pr_<level> and add
> #define pr_fmt(fmt) KBUILD_MODNAME ":%s: " fmt, __func__
> ?

It included names of functions, anyway, so agreed. Incremental patch:

(I'll fold them all and resubmit).

diff --git a/arch/arm/mach-msm/board-dream-gpio.c b/arch/arm/mach-msm/board-dream-gpio.c
index d9201f9..221c3bd 100644
--- a/arch/arm/mach-msm/board-dream-gpio.c
+++ b/arch/arm/mach-msm/board-dream-gpio.c
@@ -30,6 +30,8 @@
#undef MODULE_PARAM_PREFIX
#define MODULE_PARAM_PREFIX "board_trout."

+#define pr_fmt(fmt) KBUILD_MODNAME ":%s: " fmt, __func__
+
static uint cpld_usb_h2w_sw;
module_param_named(usb_h2w_sw, cpld_usb_h2w_sw, uint, 0);

@@ -83,7 +85,7 @@ static int dream_gpio_write(struct gpio_chip *chip, unsigned n, unsigned on)
uint8_t reg_val;

if ((reg >> 1) >= ARRAY_SIZE(dream_cpld_shadow)) {
- printk(KERN_ERR "dream_gpio_write called on input %d\n", n);
+ pr_err("called on input %d\n", n);
return -ENOTSUPP;
}

@@ -186,7 +188,7 @@ static void dream_gpio_irq_handler(unsigned int irq, struct irq_desc *desc)

if (v & int_mask) {
writeb(v & int_mask, DREAM_CPLD_BASE + stat_reg);
- printk(KERN_ERR "dream_gpio_irq_handler: got masked "
+ pr_err("got masked "
"interrupt: %d:%02x\n", bank, v & int_mask);
}

diff --git a/arch/arm/mach-msm/generic_gpio.c b/arch/arm/mach-msm/generic_gpio.c
index 5164c77..1175ffd 100644
--- a/arch/arm/mach-msm/generic_gpio.c
+++ b/arch/arm/mach-msm/generic_gpio.c
@@ -22,6 +22,8 @@

#include "gpio_chip.h"

+#define pr_fmt(fmt) KBUILD_MODNAME ":%s: " fmt, __func__
+
#define GPIO_NUM_TO_CHIP_INDEX(gpio) ((gpio)>>5)

struct gpio_state {
@@ -47,7 +49,7 @@ int register_gpio_chip(struct gpio_chip *new_gpio_chip)

new_gpio_chip->state = kzalloc(size, GFP_KERNEL);
if (new_gpio_chip->state == NULL) {
- printk(KERN_ERR "register_gpio_chip: failed to allocate state\n");
+ pr_err("failed to allocate state\n");
return -ENOMEM;
}

@@ -63,7 +65,7 @@ int register_gpio_chip(struct gpio_chip *new_gpio_chip)

new_array = kmalloc(array_size * sizeof(new_array[0]), GFP_ATOMIC);
if (!new_array) {
- printk(KERN_ERR "register_gpio_chip: failed to allocate array\n");
+ pr_err("failed to allocate array\n");
err = -ENOMEM;
goto failed;
}
@@ -81,7 +83,7 @@ int register_gpio_chip(struct gpio_chip *new_gpio_chip)
goto added;
}
if (gpio_chip->end >= new_gpio_chip->start) {
- printk(KERN_ERR "register_gpio_source %u-%u overlaps with %u-%u\n",
+ pr_err("%u-%u overlaps with %u-%u\n",
new_gpio_chip->start, new_gpio_chip->end,
gpio_chip->start, gpio_chip->end);
err = -EBUSY;


--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-09 16:18:52

by Daniel Walker

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Wed, 2009-12-09 at 12:37 +0100, Pavel Machek wrote:
> On Tue 2009-12-08 16:39:09, Arve Hj?nnev?g wrote:
> > On Tue, Dec 8, 2009 at 2:45 PM, Russell King - ARM Linux
> > <[email protected]> wrote:
> > > On Tue, Dec 08, 2009 at 11:28:43AM +0100, Pavel Machek wrote:
> > >> Add GPIO support for HTC Dream.
> > >>
> > >> Signed-off-by: Pavel Machek <[email protected]>
> > >>
> > >> diff --git a/arch/arm/mach-msm/Kconfig b/arch/arm/mach-msm/Kconfig
> > >> index f780086..774c50e 100644
> > >> --- a/arch/arm/mach-msm/Kconfig
> > >> +++ b/arch/arm/mach-msm/Kconfig
> > >> @@ -40,4 +40,8 @@ config MACH_TROUT
> > >> help
> > >> Support for the HTC Dream, T-Mobile G1, Android ADP1 devices.
> > >>
> > >> +config GENERIC_GPIO
> > >> + bool
> > >> + default y
> > >
> > > Please arrange for this to be handled just like every other ARM
> > > platform via a 'select' statement - eg:
> > >
> > > config ARCH_AT91
> > > bool "Atmel AT91"
> > > select GENERIC_GPIO
> > > select ARCH_REQUIRE_GPIOLIB
> > > select HAVE_CLK
> > >
> > > It is not nice to have multiple definitions of the same symbol scattered
> > > throughout the Kconfig files.
> > >
> >
> > Why did this code get pulled into the dream gpio code? The original
> > change that adds msm gpio support already selects GENERIC_GPIO
> > (http://android.git.kernel.org/?p=kernel/msm.git;a=commit;h=5ae9f4403530a5782478c35d29753081750c4188).
> > Since you copied half of the files from that change anyway, it would
> > be better to just include that change in you patch set.
>
> I'm not sure how to do that with git without pulling all the changes
> before that one, too :-(.

I'm going to end up pulling a lot of these git commit into my git tree.
It would be pretty easy for me to just pull this GPIO change directly ..
I assume you haven't found a way to work with git that suites you? It
would be best if you used git, but I could try to do some sort of quilt
export if that works better for you.

Daniel

2009-12-09 23:40:06

by Ryan Mallon

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

Ryan Mallon wrote:
> Pavel Machek wrote:
>> Add GPIO support for HTC Dream.
>>
>> Signed-off-by: Pavel Machek <[email protected]>
>>
>> +int register_gpio_chip(struct gpio_chip *new_gpio_chip)
>> +{

...

>
> This is still really screwy. Why are you creating your own version of
> struct gpio_chip in addition to the one in include/asm-generic/gpio.h
> (which you also appear to include in some places). It makes the code
> extremely confusing. Other architectures use wrapper structures. Can you
> have something like this instead:
>
> struct dream_gpio_chip {
> struct gpio_chip chip;
>
> /* Dream specific bits */
> };
>
> The name of this function also needs to be changed to something less
> generic since it is being exported globally.
>
> I also think this function is doing way to much work for what it is.
> Does it really need to be this complicated?

Further to this, I think it is worth doing the work to make this gpiolib
now. Most of the other ARM chips now support gpiolib, so it would seem a
bit of a step backwards to start adding new chips which don't. I think
that adding the gpiolib support will also cleanup the mess that is
register_gpio_chip, since this is all already handled by the gpiolib core.

~Ryan

--
Bluewater Systems Ltd - ARM Technology Solution Centre

Ryan Mallon 5 Amuri Park, 404 Barbadoes St
[email protected] PO Box 13 889, Christchurch 8013
http://www.bluewatersys.com New Zealand
Phone: +64 3 3779127 Freecall: Australia 1800 148 751
Fax: +64 3 3779135 USA 1800 261 2934

2009-12-10 16:26:49

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

Hi!

> >>> +#define DREAM_INT_TO_BANK(n) ((n - DREAM_INT_START) / DREAM_INT_BANK0_COUNT)
> >>> +#define DREAM_INT_TO_MASK(n) (1U << ((n - DREAM_INT_START) & 7))
> >>> +#define DREAM_BANK_TO_MASK_REG(bank) \
> >>> + (bank ? DREAM_GPIO_INT_MASK1_REG : DREAM_GPIO_INT_MASK0_REG)
> >>> +#define DREAM_BANK_TO_STAT_REG(bank) \
> >>> + (bank ? DREAM_GPIO_INT_STAT1_REG : DREAM_GPIO_INT_STAT0_REG)
> >> Are these needed outside of the gpiolib code? If not, they should be
> >> moved there. I also think they should have lower case names since they
> >> act like a function, and make the code where they are used nicer to
> >> read.
> >
> > I guess these logically belong here.
> >
> > No, macros are macros, that means upcase.
>
> container_of, min, swap, etc are macros too. It is easier to read this
> if they are lower case because they are typically used for initialising
> variables, ie:
>
> int bank = dream_int_to_bank(irq);
>
> Is easier (IMHO) to read than:
>
> int bank = DREAM_INT_TO_BANK(irq);

I disagree here. I could convert it to inline function, but I guess it
is okay as it is.

> > static void __init dream_init(void)
> > {
> > + gpio_set_value(DREAM_GPIO_UI_LED_EN, 1);
> > + mdelay(300);
> > + gpio_set_value(DREAM_GPIO_UI_LED_EN, 0);
> > + mdelay(300);
> > + gpio_set_value(DREAM_GPIO_UI_LED_EN, 1);
> > + mdelay(300);
> > + gpio_set_value(DREAM_GPIO_UI_LED_EN, 0);
> > + mdelay(300);
> > + gpio_set_value(DREAM_GPIO_UI_LED_EN, 1);
> > + mdelay(300);
> > + gpio_set_value(DREAM_GPIO_UI_LED_EN, 0);
> > + mdelay(300);
> > + gpio_set_value(DREAM_GPIO_UI_LED_EN, 1);
> > + mdelay(300);
> > + gpio_set_value(DREAM_GPIO_UI_LED_EN, 0);
> > + mdelay(300);
> > +
>
> Indentation looks screwy here. Also, is this meant to blink the leds?
> There is a 2.4 second hard delay here, which is horrible.

Yep, that was my debugging code, not meant for upstream. And yes, its
blinking.
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-10 16:27:40

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Wed 2009-12-09 03:42:43, Arve Hj?nnev?g wrote:
> On Wed, Dec 9, 2009 at 3:37 AM, Pavel Machek <[email protected]> wrote:
> > On Tue 2009-12-08 16:39:09, Arve Hj?nnev?g wrote:
> >> On Tue, Dec 8, 2009 at 2:45 PM, Russell King - ARM Linux
> >> <[email protected]> wrote:
> >> > On Tue, Dec 08, 2009 at 11:28:43AM +0100, Pavel Machek wrote:
> >> >> Add GPIO support for HTC Dream.
> >> >>
> >> >> Signed-off-by: Pavel Machek <[email protected]>
> >> >>
> >> >> diff --git a/arch/arm/mach-msm/Kconfig b/arch/arm/mach-msm/Kconfig
> >> >> index f780086..774c50e 100644
> >> >> --- a/arch/arm/mach-msm/Kconfig
> >> >> +++ b/arch/arm/mach-msm/Kconfig
> >> >> @@ -40,4 +40,8 @@ config MACH_TROUT
> >> >> ? ? ? help
> >> >> ? ? ? ? Support for the HTC Dream, T-Mobile G1, Android ADP1 devices.
> >> >>
> >> >> +config GENERIC_GPIO
> >> >> + ? ? bool
> >> >> + ? ? default y
> >> >
> >> > Please arrange for this to be handled just like every other ARM
> >> > platform via a 'select' statement - eg:
> >> >
> >> > config ARCH_AT91
> >> > ? ? ? ?bool "Atmel AT91"
> >> > ? ? ? ?select GENERIC_GPIO
> >> > ? ? ? ?select ARCH_REQUIRE_GPIOLIB
> >> > ? ? ? ?select HAVE_CLK
> >> >
> >> > It is not nice to have multiple definitions of the same symbol scattered
> >> > throughout the Kconfig files.
> >> >
> >>
> >> Why did this code get pulled into the dream gpio code? The original
> >> change that adds msm gpio support already selects GENERIC_GPIO
> >> (http://android.git.kernel.org/?p=kernel/msm.git;a=commit;h=5ae9f4403530a5782478c35d29753081750c4188).
> >> Since you copied half of the files from that change anyway, it would
> >> be better to just include that change in you patch set.
> >
> > I'm not sure how to do that with git without pulling all the changes
> > before that one, too :-(.
>
> git cherry-pick

Ok, I'll try to remember that. But I do not push patches using git, so
I'm not sure how much difference it would make.
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-10 16:57:26

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

Hi!

> This is still really screwy. Why are you creating your own version of
> struct gpio_chip in addition to the one in include/asm-generic/gpio.h
> (which you also appear to include in some places). It makes the code
> extremely confusing. Other architectures use wrapper structures. Can you
> have something like this instead:
>
> struct dream_gpio_chip {
> struct gpio_chip chip;
>
> /* Dream specific bits */
> };

Well, unfortunately dream's gpio_chip definition is completely
different to the one from include/asm-generic. I'll do the rename.

> The name of this function also needs to be changed to something less
> generic since it is being exported globally.

Well, arm only ever supports one subarch, so...

Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-10 17:25:11

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

Hi!

> > This is still really screwy. Why are you creating your own version of
> > struct gpio_chip in addition to the one in include/asm-generic/gpio.h
> > (which you also appear to include in some places). It makes the code
> > extremely confusing. Other architectures use wrapper structures. Can you
> > have something like this instead:
> >
> > struct dream_gpio_chip {
> > struct gpio_chip chip;
> >
> > /* Dream specific bits */
> > };
> >
> > The name of this function also needs to be changed to something less
> > generic since it is being exported globally.
> >
> > I also think this function is doing way to much work for what it is.
> > Does it really need to be this complicated?
>
> Further to this, I think it is worth doing the work to make this gpiolib
> now. Most of the other ARM chips now support gpiolib, so it would seem a
> bit of a step backwards to start adding new chips which don't. I think
> that adding the gpiolib support will also cleanup the mess that is
> register_gpio_chip, since this is all already handled by the gpiolib core.

I tried going through drivers/gpio/gpiolib.c and it seems to be a lot
of code -- mostly sysrq interface to userland. I'm not sure how much
code could be shared...

Anyway, here's latest version.

Signed-off-by: Pavel Machek <[email protected]>
Pavel

diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig
index 1c4119c..db622a5 100644
--- a/arch/arm/Kconfig
+++ b/arch/arm/Kconfig
@@ -565,6 +565,7 @@ config ARCH_MSM
select CPU_V6
select GENERIC_TIME
select GENERIC_CLOCKEVENTS
+ select GENERIC_GPIO
help
Support for Qualcomm MSM7K based systems. This runs on the ARM11
apps processor of the MSM7K and depends on a shared memory
diff --git a/arch/arm/mach-msm/Makefile b/arch/arm/mach-msm/Makefile
index 91e6f5c..4c2567e 100644
--- a/arch/arm/mach-msm/Makefile
+++ b/arch/arm/mach-msm/Makefile
@@ -6,4 +6,4 @@ obj-y += clock.o clock-7x01a.o

obj-$(CONFIG_MACH_HALIBUT) += board-halibut.o

-obj-$(CONFIG_MACH_TROUT) += board-dream.o
+obj-$(CONFIG_MACH_TROUT) += board-dream.o board-dream-gpio.o generic_gpio.o
diff --git a/arch/arm/mach-msm/board-dream-gpio.c b/arch/arm/mach-msm/board-dream-gpio.c
new file mode 100644
index 0000000..4381b62
--- /dev/null
+++ b/arch/arm/mach-msm/board-dream-gpio.c
@@ -0,0 +1,288 @@
+/* arch/arm/mach-msm/board-dream-gpio.c
+ *
+ * Copyright (C) 2008 Google, Inc.
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that 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.
+ *
+ */
+
+#define pr_fmt(fmt) KBUILD_MODNAME ":%s: " fmt, __func__
+
+#include <linux/kernel.h>
+#include <linux/errno.h>
+#include <linux/irq.h>
+#include <linux/pm.h>
+#include <linux/sysdev.h>
+#include <linux/io.h>
+#include <linux/gpio.h>
+
+#include <asm/mach-types.h>
+
+#include "board-dream.h"
+#include "gpio_chip.h"
+
+/* We want to be compatible with existing bootloaders */
+#undef MODULE_PARAM_PREFIX
+#define MODULE_PARAM_PREFIX "board_trout."
+
+static uint cpld_usb_h2w_sw;
+module_param_named(usb_h2w_sw, cpld_usb_h2w_sw, uint, 0);
+
+static uint8_t dream_cpld_shadow[4] = {
+#if defined(CONFIG_MSM_DEBUG_UART1)
+ /* H2W pins <-> UART1 */
+ [0] = 0x40, /* for serial debug, low current */
+#else
+ /* H2W pins <-> UART3, Bluetooth <-> UART1 */
+ [0] = 0x80, /* for serial debug, low current */
+#endif
+ [1] = 0x04, /* I2C_PULL */
+ [3] = 0x04, /* mmdi 32k en */
+};
+static uint8_t dream_int_mask[2] = {
+ [0] = 0xff, /* mask all interrupts */
+ [1] = 0xff,
+};
+static uint8_t dream_sleep_int_mask[] = {
+ [0] = 0xff,
+ [1] = 0xff,
+};
+static int dream_suspended;
+
+static int dream_gpio_read(struct msm_gpio_chip *chip, unsigned n)
+{
+ uint8_t b;
+ int reg;
+ if (n >= DREAM_GPIO_VIRTUAL_BASE)
+ n += DREAM_GPIO_VIRTUAL_TO_REAL_OFFSET;
+ b = 1U << (n & 7);
+ reg = (n & 0x78) >> 2; /* assumes base is 128 */
+ return !!(readb(DREAM_CPLD_BASE + reg) & b);
+}
+
+static uint8_t dream_gpio_write_shadow(unsigned n, unsigned on)
+{
+ uint8_t b = 1U << (n & 7);
+ int reg = (n & 0x78) >> 2; /* assumes base is 128 */
+
+ if (on)
+ return dream_cpld_shadow[reg >> 1] |= b;
+ else
+ return dream_cpld_shadow[reg >> 1] &= ~b;
+}
+
+static int dream_gpio_write(struct msm_gpio_chip *chip, unsigned n, unsigned on)
+{
+ int reg = (n & 0x78) >> 2; /* assumes base is 128 */
+ unsigned long flags;
+ uint8_t reg_val;
+
+ if ((reg >> 1) >= ARRAY_SIZE(dream_cpld_shadow)) {
+ pr_err("called on input %d\n", n);
+ return -ENOTSUPP;
+ }
+
+ local_irq_save(flags);
+ reg_val = dream_gpio_write_shadow(n, on);
+ writeb(reg_val, DREAM_CPLD_BASE + reg);
+ local_irq_restore(flags);
+ return 0;
+}
+
+static int dream_gpio_configure(struct msm_gpio_chip *chip, unsigned int gpio, unsigned long flags)
+{
+ if (flags & (GPIOF_OUTPUT_LOW | GPIOF_OUTPUT_HIGH))
+ dream_gpio_write(chip, gpio, flags & GPIOF_OUTPUT_HIGH);
+ return 0;
+}
+
+static int dream_gpio_get_irq_num(struct msm_gpio_chip *chip, unsigned int gpio, unsigned int *irqp, unsigned long *irqnumflagsp)
+{
+ if ((gpio < DREAM_GPIO_BANK0_FIRST_INT_SOURCE ||
+ gpio > DREAM_GPIO_BANK0_LAST_INT_SOURCE) &&
+ (gpio < DREAM_GPIO_BANK1_FIRST_INT_SOURCE ||
+ gpio > DREAM_GPIO_BANK1_LAST_INT_SOURCE))
+ return -ENOENT;
+ *irqp = DREAM_GPIO_TO_INT(gpio);
+ if (irqnumflagsp)
+ *irqnumflagsp = 0;
+ return 0;
+}
+
+static void dream_gpio_irq_ack(unsigned int irq)
+{
+ int bank = DREAM_INT_TO_BANK(irq);
+ uint8_t mask = DREAM_INT_TO_MASK(irq);
+ int reg = DREAM_BANK_TO_STAT_REG(bank);
+
+ writeb(mask, DREAM_CPLD_BASE + reg);
+}
+
+static void dream_gpio_irq_mask(unsigned int irq)
+{
+ unsigned long flags;
+ uint8_t reg_val;
+ int bank = DREAM_INT_TO_BANK(irq);
+ uint8_t mask = DREAM_INT_TO_MASK(irq);
+ int reg = DREAM_BANK_TO_MASK_REG(bank);
+
+ local_irq_save(flags);
+ reg_val = dream_int_mask[bank] |= mask;
+
+ if (!dream_suspended)
+ writeb(reg_val, DREAM_CPLD_BASE + reg);
+ local_irq_restore(flags);
+}
+
+static void dream_gpio_irq_unmask(unsigned int irq)
+{
+ unsigned long flags;
+ uint8_t reg_val;
+ int bank = DREAM_INT_TO_BANK(irq);
+ uint8_t mask = DREAM_INT_TO_MASK(irq);
+ int reg = DREAM_BANK_TO_MASK_REG(bank);
+
+ local_irq_save(flags);
+ reg_val = dream_int_mask[bank] &= ~mask;
+
+ if (!dream_suspended)
+ writeb(reg_val, DREAM_CPLD_BASE + reg);
+ local_irq_restore(flags);
+}
+
+int dream_gpio_irq_set_wake(unsigned int irq, unsigned int on)
+{
+ unsigned long flags;
+ int bank = DREAM_INT_TO_BANK(irq);
+ uint8_t mask = DREAM_INT_TO_MASK(irq);
+
+ local_irq_save(flags);
+ if (on)
+ dream_sleep_int_mask[bank] &= ~mask;
+ else
+ dream_sleep_int_mask[bank] |= mask;
+ local_irq_restore(flags);
+ return 0;
+}
+
+static void dream_gpio_irq_handler(unsigned int irq, struct irq_desc *desc)
+{
+ int j, m;
+ unsigned v;
+ int bank;
+ int stat_reg;
+ int int_base = DREAM_INT_START;
+ uint8_t int_mask;
+
+ for (bank = 0; bank < 2; bank++) {
+ stat_reg = DREAM_BANK_TO_STAT_REG(bank);
+ v = readb(DREAM_CPLD_BASE + stat_reg);
+ int_mask = dream_int_mask[bank];
+
+ if (v & int_mask) {
+ writeb(v & int_mask, DREAM_CPLD_BASE + stat_reg);
+ pr_err("got masked "
+ "interrupt: %d:%02x\n", bank, v & int_mask);
+ }
+
+ v &= ~int_mask;
+ while (v) {
+ m = v & -v;
+ j = fls(m) - 1;
+ v &= ~m;
+ generic_handle_irq(int_base + j);
+ }
+ int_base += DREAM_INT_BANK0_COUNT;
+ }
+ desc->chip->ack(irq);
+}
+
+static int dream_sysdev_suspend(struct sys_device *dev, pm_message_t state)
+{
+ dream_suspended = 1;
+ writeb(dream_sleep_int_mask[0],
+ DREAM_CPLD_BASE + DREAM_GPIO_INT_MASK0_REG);
+ writeb(dream_sleep_int_mask[1],
+ DREAM_CPLD_BASE + DREAM_GPIO_INT_MASK1_REG);
+ writeb(dream_sleep_int_mask[0],
+ DREAM_CPLD_BASE + DREAM_GPIO_INT_STAT0_REG);
+ writeb(dream_sleep_int_mask[1],
+ DREAM_CPLD_BASE + DREAM_GPIO_INT_STAT1_REG);
+ return 0;
+}
+
+int dream_sysdev_resume(struct sys_device *dev)
+{
+ writeb(dream_int_mask[0], DREAM_CPLD_BASE + DREAM_GPIO_INT_MASK0_REG);
+ writeb(dream_int_mask[1], DREAM_CPLD_BASE + DREAM_GPIO_INT_MASK1_REG);
+ dream_suspended = 0;
+ return 0;
+}
+
+static struct irq_chip dream_gpio_irq_chip = {
+ .name = "dreamgpio",
+ .ack = dream_gpio_irq_ack,
+ .mask = dream_gpio_irq_mask,
+ .unmask = dream_gpio_irq_unmask,
+ .set_wake = dream_gpio_irq_set_wake,
+};
+
+static struct msm_gpio_chip dream_gpio_chip = {
+ .start = DREAM_GPIO_START,
+ .end = DREAM_GPIO_END,
+ .configure = dream_gpio_configure,
+ .get_irq_num = dream_gpio_get_irq_num,
+ .read = dream_gpio_read,
+ .write = dream_gpio_write,
+};
+
+struct sysdev_class dream_sysdev_class = {
+ .name = "dreamgpio_irq",
+ .suspend = dream_sysdev_suspend,
+ .resume = dream_sysdev_resume,
+};
+
+static struct sys_device dream_irq_device = {
+ .cls = &dream_sysdev_class,
+};
+
+static int __init dream_init_gpio(void)
+{
+ int i;
+
+ if (!machine_is_trout())
+ return 0;
+
+ /* adjust GPIOs based on bootloader request */
+ pr_info("dream_init_gpio: cpld_usb_hw2_sw = %d\n", cpld_usb_h2w_sw);
+ dream_gpio_write_shadow(DREAM_GPIO_USB_H2W_SW, cpld_usb_h2w_sw);
+
+ for (i = 0; i < ARRAY_SIZE(dream_cpld_shadow); i++)
+ writeb(dream_cpld_shadow[i], DREAM_CPLD_BASE + i * 2);
+
+ for (i = DREAM_INT_START; i <= DREAM_INT_END; i++) {
+ set_irq_chip(i, &dream_gpio_irq_chip);
+ set_irq_handler(i, handle_edge_irq);
+ set_irq_flags(i, IRQF_VALID);
+ }
+
+ register_msm_gpio_chip(&dream_gpio_chip);
+
+ set_irq_type(MSM_GPIO_TO_INT(17), IRQF_TRIGGER_HIGH);
+ set_irq_chained_handler(MSM_GPIO_TO_INT(17), dream_gpio_irq_handler);
+ set_irq_wake(MSM_GPIO_TO_INT(17), 1);
+
+ if (sysdev_class_register(&dream_sysdev_class) == 0)
+ sysdev_register(&dream_irq_device);
+
+ return 0;
+}
+
+postcore_initcall(dream_init_gpio);
diff --git a/arch/arm/mach-msm/board-dream.c b/arch/arm/mach-msm/board-dream.c
index d238e2c..edefacf 100644
--- a/arch/arm/mach-msm/board-dream.c
+++ b/arch/arm/mach-msm/board-dream.c
@@ -18,6 +18,8 @@
#include <linux/kernel.h>
#include <linux/init.h>
#include <linux/platform_device.h>
+#include <linux/delay.h>
+#include <linux/gpio.h>

#include <asm/mach-types.h>
#include <asm/mach/arch.h>
@@ -57,14 +59,31 @@ static void __init dream_fixup(struct machine_desc *desc, struct tag *tags,

static void __init dream_init(void)
{
+ gpio_set_value(DREAM_GPIO_UI_LED_EN, 1);
+ mdelay(300);
+ gpio_set_value(DREAM_GPIO_UI_LED_EN, 0);
+ mdelay(300);
+ gpio_set_value(DREAM_GPIO_UI_LED_EN, 1);
+ mdelay(300);
+ gpio_set_value(DREAM_GPIO_UI_LED_EN, 0);
+ mdelay(300);
+ gpio_set_value(DREAM_GPIO_UI_LED_EN, 1);
+ mdelay(300);
+ gpio_set_value(DREAM_GPIO_UI_LED_EN, 0);
+ mdelay(300);
+ gpio_set_value(DREAM_GPIO_UI_LED_EN, 1);
+ mdelay(300);
+ gpio_set_value(DREAM_GPIO_UI_LED_EN, 0);
+ mdelay(300);
+
platform_add_devices(devices, ARRAY_SIZE(devices));
}

static struct map_desc dream_io_desc[] __initdata = {
{
- .virtual = TROUT_CPLD_BASE,
- .pfn = __phys_to_pfn(TROUT_CPLD_START),
- .length = TROUT_CPLD_SIZE,
+ .virtual = DREAM_CPLD_BASE,
+ .pfn = __phys_to_pfn(DREAM_CPLD_START),
+ .length = DREAM_CPLD_SIZE,
.type = MT_DEVICE_NONSHARED
}
};
@@ -76,7 +95,7 @@ static void __init dream_map_io(void)

#ifdef CONFIG_MSM_DEBUG_UART3
/* route UART3 to the "H2W" extended usb connector */
- writeb(0x80, TROUT_CPLD_BASE + 0x00);
+ writeb(0x80, DREAM_CPLD_BASE + 0x00);
#endif

msm_clock_init();
diff --git a/arch/arm/mach-msm/board-dream.h b/arch/arm/mach-msm/board-dream.h
index 4f345a5..aab1faf 100644
--- a/arch/arm/mach-msm/board-dream.h
+++ b/arch/arm/mach-msm/board-dream.h
@@ -1,5 +1,153 @@

-#define TROUT_CPLD_BASE 0xE8100000
-#define TROUT_CPLD_START 0x98000000
-#define TROUT_CPLD_SIZE SZ_4K
+#define MSM_SMI_BASE 0x00000000
+#define MSM_SMI_SIZE 0x00800000

+#define MSM_EBI_BASE 0x10000000
+#define MSM_EBI_SIZE 0x06e00000
+
+#define MSM_PMEM_GPU0_BASE 0x00000000
+#define MSM_PMEM_GPU0_SIZE 0x00700000
+
+#define MSM_PMEM_MDP_BASE 0x02000000
+#define MSM_PMEM_MDP_SIZE 0x00800000
+
+#define MSM_PMEM_ADSP_BASE 0x02800000
+#define MSM_PMEM_ADSP_SIZE 0x00800000
+
+#define MSM_PMEM_CAMERA_BASE 0x03000000
+#define MSM_PMEM_CAMERA_SIZE 0x00800000
+
+#define MSM_FB_BASE 0x03800000
+#define MSM_FB_SIZE 0x00100000
+
+#define MSM_LINUX_BASE MSM_EBI_BASE
+#define MSM_LINUX_SIZE 0x06500000
+
+#define MSM_PMEM_GPU1_SIZE 0x800000
+#define MSM_PMEM_GPU1_BASE (MSM_RAM_CONSOLE_BASE - MSM_PMEM_GPU1_SIZE)
+
+#define MSM_RAM_CONSOLE_BASE (MSM_EBI_BASE + 0x6d00000)
+#define MSM_RAM_CONSOLE_SIZE (128 * SZ_1K)
+
+#if (MSM_FB_BASE + MSM_FB_SIZE) >= (MSM_PMEM_GPU1_BASE)
+#error invalid memory map
+#endif
+
+#define DECLARE_MSM_IOMAP
+#include <mach/msm_iomap.h>
+
+#define DREAM_4_BALL_UP_0 1
+#define DREAM_4_BALL_LEFT_0 18
+#define DREAM_4_BALL_DOWN_0 57
+#define DREAM_4_BALL_RIGHT_0 91
+
+#define DREAM_5_BALL_UP_0 94
+#define DREAM_5_BALL_LEFT_0 18
+#define DREAM_5_BALL_DOWN_0 90
+#define DREAM_5_BALL_RIGHT_0 19
+
+#define DREAM_POWER_KEY 20
+
+#define DREAM_4_TP_LS_EN 19
+#define DREAM_5_TP_LS_EN 1
+
+#define DREAM_CPLD_BASE 0xE8100000
+#define DREAM_CPLD_START 0x98000000
+#define DREAM_CPLD_SIZE SZ_4K
+
+#define DREAM_GPIO_CABLE_IN1 (83)
+#define DREAM_GPIO_CABLE_IN2 (49)
+
+#define DREAM_GPIO_START (128)
+
+#define DREAM_GPIO_INT_MASK0_REG (0x0c)
+#define DREAM_GPIO_INT_STAT0_REG (0x0e)
+#define DREAM_GPIO_INT_MASK1_REG (0x14)
+#define DREAM_GPIO_INT_STAT1_REG (0x10)
+
+#define DREAM_GPIO_HAPTIC_PWM (28)
+#define DREAM_GPIO_PS_HOLD (25)
+
+#define DREAM_GPIO_MISC2_BASE (DREAM_GPIO_START + 0x00)
+#define DREAM_GPIO_MISC3_BASE (DREAM_GPIO_START + 0x08)
+#define DREAM_GPIO_MISC4_BASE (DREAM_GPIO_START + 0x10)
+#define DREAM_GPIO_MISC5_BASE (DREAM_GPIO_START + 0x18)
+#define DREAM_GPIO_INT2_BASE (DREAM_GPIO_START + 0x20)
+#define DREAM_GPIO_MISC1_BASE (DREAM_GPIO_START + 0x28)
+#define DREAM_GPIO_VIRTUAL_BASE (DREAM_GPIO_START + 0x30)
+#define DREAM_GPIO_INT5_BASE (DREAM_GPIO_START + 0x48)
+
+#define DREAM_GPIO_CHARGER_EN (DREAM_GPIO_MISC2_BASE + 0)
+#define DREAM_GPIO_ISET (DREAM_GPIO_MISC2_BASE + 1)
+#define DREAM_GPIO_H2W_DAT_DIR (DREAM_GPIO_MISC2_BASE + 2)
+#define DREAM_GPIO_H2W_CLK_DIR (DREAM_GPIO_MISC2_BASE + 3)
+#define DREAM_GPIO_H2W_DAT_GPO (DREAM_GPIO_MISC2_BASE + 4)
+#define DREAM_GPIO_H2W_CLK_GPO (DREAM_GPIO_MISC2_BASE + 5)
+#define DREAM_GPIO_H2W_SEL0 (DREAM_GPIO_MISC2_BASE + 6)
+#define DREAM_GPIO_H2W_SEL1 (DREAM_GPIO_MISC2_BASE + 7)
+
+#define DREAM_GPIO_SPOTLIGHT_EN (DREAM_GPIO_MISC3_BASE + 0)
+#define DREAM_GPIO_FLASH_EN (DREAM_GPIO_MISC3_BASE + 1)
+#define DREAM_GPIO_I2C_PULL (DREAM_GPIO_MISC3_BASE + 2)
+#define DREAM_GPIO_TP_I2C_PULL (DREAM_GPIO_MISC3_BASE + 3)
+#define DREAM_GPIO_TP_EN (DREAM_GPIO_MISC3_BASE + 4)
+#define DREAM_GPIO_JOG_EN (DREAM_GPIO_MISC3_BASE + 5)
+#define DREAM_GPIO_UI_LED_EN (DREAM_GPIO_MISC3_BASE + 6)
+#define DREAM_GPIO_QTKEY_LED_EN (DREAM_GPIO_MISC3_BASE + 7)
+
+#define DREAM_GPIO_VCM_PWDN (DREAM_GPIO_MISC4_BASE + 0)
+#define DREAM_GPIO_USB_H2W_SW (DREAM_GPIO_MISC4_BASE + 1)
+#define DREAM_GPIO_COMPASS_RST_N (DREAM_GPIO_MISC4_BASE + 2)
+#define DREAM_GPIO_HAPTIC_EN_UP (DREAM_GPIO_MISC4_BASE + 3)
+#define DREAM_GPIO_HAPTIC_EN_MAIN (DREAM_GPIO_MISC4_BASE + 4)
+#define DREAM_GPIO_USB_PHY_RST_N (DREAM_GPIO_MISC4_BASE + 5)
+#define DREAM_GPIO_WIFI_PA_RESETX (DREAM_GPIO_MISC4_BASE + 6)
+#define DREAM_GPIO_WIFI_EN (DREAM_GPIO_MISC4_BASE + 7)
+
+#define DREAM_GPIO_BT_32K_EN (DREAM_GPIO_MISC5_BASE + 0)
+#define DREAM_GPIO_MAC_32K_EN (DREAM_GPIO_MISC5_BASE + 1)
+#define DREAM_GPIO_MDDI_32K_EN (DREAM_GPIO_MISC5_BASE + 2)
+#define DREAM_GPIO_COMPASS_32K_EN (DREAM_GPIO_MISC5_BASE + 3)
+
+#define DREAM_GPIO_NAVI_ACT_N (DREAM_GPIO_INT2_BASE + 0)
+#define DREAM_GPIO_COMPASS_IRQ (DREAM_GPIO_INT2_BASE + 1)
+#define DREAM_GPIO_SLIDING_DET (DREAM_GPIO_INT2_BASE + 2)
+#define DREAM_GPIO_AUD_HSMIC_DET_N (DREAM_GPIO_INT2_BASE + 3)
+#define DREAM_GPIO_SD_DOOR_N (DREAM_GPIO_INT2_BASE + 4)
+#define DREAM_GPIO_CAM_BTN_STEP1_N (DREAM_GPIO_INT2_BASE + 5)
+#define DREAM_GPIO_CAM_BTN_STEP2_N (DREAM_GPIO_INT2_BASE + 6)
+#define DREAM_GPIO_TP_ATT_N (DREAM_GPIO_INT2_BASE + 7)
+#define DREAM_GPIO_BANK0_FIRST_INT_SOURCE (DREAM_GPIO_NAVI_ACT_N)
+#define DREAM_GPIO_BANK0_LAST_INT_SOURCE (DREAM_GPIO_TP_ATT_N)
+
+#define DREAM_GPIO_H2W_DAT_GPI (DREAM_GPIO_MISC1_BASE + 0)
+#define DREAM_GPIO_H2W_CLK_GPI (DREAM_GPIO_MISC1_BASE + 1)
+#define DREAM_GPIO_CPLD128_VER_0 (DREAM_GPIO_MISC1_BASE + 4)
+#define DREAM_GPIO_CPLD128_VER_1 (DREAM_GPIO_MISC1_BASE + 5)
+#define DREAM_GPIO_CPLD128_VER_2 (DREAM_GPIO_MISC1_BASE + 6)
+#define DREAM_GPIO_CPLD128_VER_3 (DREAM_GPIO_MISC1_BASE + 7)
+
+#define DREAM_GPIO_SDMC_CD_N (DREAM_GPIO_VIRTUAL_BASE + 0)
+#define DREAM_GPIO_END (DREAM_GPIO_SDMC_CD_N)
+#define DREAM_GPIO_BANK1_FIRST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
+#define DREAM_GPIO_BANK1_LAST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
+
+#define DREAM_GPIO_VIRTUAL_TO_REAL_OFFSET \
+ (DREAM_GPIO_INT5_BASE - DREAM_GPIO_VIRTUAL_BASE)
+
+#define DREAM_INT_START (NR_MSM_IRQS + NR_GPIO_IRQS)
+#define DREAM_INT_BANK0_COUNT (8)
+#define DREAM_INT_BANK1_START (DREAM_INT_START + DREAM_INT_BANK0_COUNT)
+#define DREAM_INT_BANK1_COUNT (1)
+#define DREAM_INT_END (DREAM_INT_START + DREAM_INT_BANK0_COUNT + \
+ DREAM_INT_BANK1_COUNT - 1)
+#define DREAM_GPIO_TO_INT(n) (((n) <= DREAM_GPIO_BANK0_LAST_INT_SOURCE) ? \
+ (DREAM_INT_START - DREAM_GPIO_BANK0_FIRST_INT_SOURCE + (n)) : \
+ (DREAM_INT_BANK1_START - DREAM_GPIO_BANK1_FIRST_INT_SOURCE + (n)))
+
+#define DREAM_INT_TO_BANK(n) ((n - DREAM_INT_START) / DREAM_INT_BANK0_COUNT)
+#define DREAM_INT_TO_MASK(n) (1U << ((n - DREAM_INT_START) & 7))
+#define DREAM_BANK_TO_MASK_REG(bank) \
+ (bank ? DREAM_GPIO_INT_MASK1_REG : DREAM_GPIO_INT_MASK0_REG)
+#define DREAM_BANK_TO_STAT_REG(bank) \
+ (bank ? DREAM_GPIO_INT_STAT1_REG : DREAM_GPIO_INT_STAT0_REG)
diff --git a/arch/arm/mach-msm/generic_gpio.c b/arch/arm/mach-msm/generic_gpio.c
new file mode 100644
index 0000000..6644741
--- /dev/null
+++ b/arch/arm/mach-msm/generic_gpio.c
@@ -0,0 +1,285 @@
+/* arch/arm/mach-msm/generic_gpio.c
+ *
+ * Copyright (C) 2007 Google, Inc.
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that 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.
+ *
+ */
+
+#define pr_fmt(fmt) KBUILD_MODNAME ":%s: " fmt, __func__
+
+#include <linux/kernel.h>
+#include <linux/module.h>
+#include <linux/errno.h>
+#include <linux/slab.h>
+#include <linux/spinlock.h>
+#include <linux/gpio.h>
+
+#include "gpio_chip.h"
+
+#define GPIO_NUM_TO_CHIP_INDEX(gpio) ((gpio)>>5)
+
+struct gpio_state {
+ unsigned long flags;
+ int refcount;
+};
+
+static DEFINE_SPINLOCK(gpio_chips_lock);
+static LIST_HEAD(gpio_chip_list);
+static struct msm_gpio_chip **gpio_chip_array;
+static unsigned long gpio_chip_array_size;
+
+int register_msm_gpio_chip(struct msm_gpio_chip *new_gpio_chip)
+{
+ int err = 0;
+ struct msm_gpio_chip *gpio_chip;
+ int i;
+ unsigned long irq_flags;
+ /* Start/end indexes into chip array */
+ unsigned int start, end;
+ int size = (new_gpio_chip->end + 1 - new_gpio_chip->start) *
+ sizeof(new_gpio_chip->state[0]);
+
+ new_gpio_chip->state = kzalloc(size, GFP_KERNEL);
+ if (new_gpio_chip->state == NULL) {
+ pr_err("failed to allocate state\n");
+ return -ENOMEM;
+ }
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ start = GPIO_NUM_TO_CHIP_INDEX(new_gpio_chip->start);
+ end = GPIO_NUM_TO_CHIP_INDEX(new_gpio_chip->end);
+
+ if (end >= gpio_chip_array_size) {
+ /* New gpio chip array */
+ struct msm_gpio_chip **new_array;
+ /* Size of gpio chip array */
+ unsigned long array_size = end + 1;
+
+ new_array = kmalloc(array_size * sizeof(new_array[0]), GFP_ATOMIC);
+ if (!new_array) {
+ pr_err("failed to allocate array\n");
+ err = -ENOMEM;
+ goto failed;
+ }
+ for (i = 0; i < gpio_chip_array_size; i++)
+ new_array[i] = gpio_chip_array[i];
+ for (i = gpio_chip_array_size; i < array_size; i++)
+ new_array[i] = NULL;
+ gpio_chip_array = new_array;
+ gpio_chip_array_size = array_size;
+ }
+
+ list_for_each_entry(gpio_chip, &gpio_chip_list, list) {
+ if (gpio_chip->start > new_gpio_chip->end) {
+ list_add_tail(&new_gpio_chip->list, &gpio_chip->list);
+ goto added;
+ }
+ if (gpio_chip->end >= new_gpio_chip->start) {
+ pr_err("%u-%u overlaps with %u-%u\n",
+ new_gpio_chip->start, new_gpio_chip->end,
+ gpio_chip->start, gpio_chip->end);
+ err = -EBUSY;
+ goto failed;
+ }
+ }
+
+ list_add_tail(&new_gpio_chip->list, &gpio_chip_list);
+added:
+ for (i = start; i <= end; i++) {
+ if ((!gpio_chip_array[i]) || gpio_chip_array[i]->start > new_gpio_chip->start)
+ gpio_chip_array[i] = new_gpio_chip;
+ }
+failed:
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ if (err)
+ kfree(new_gpio_chip->state);
+ return err;
+}
+
+static struct msm_gpio_chip *get_gpio_chip_locked(unsigned int gpio)
+{
+ unsigned long i;
+ struct msm_gpio_chip *chip;
+
+ i = GPIO_NUM_TO_CHIP_INDEX(gpio);
+ if (i >= gpio_chip_array_size)
+ return NULL;
+ chip = gpio_chip_array[i];
+ if (chip == NULL)
+ return NULL;
+ list_for_each_entry_from(chip, &gpio_chip_list, list) {
+ if (gpio < chip->start)
+ return NULL;
+ if (gpio <= chip->end)
+ return chip;
+ }
+ return NULL;
+}
+
+static int request_gpio(unsigned int gpio, unsigned long flags)
+{
+ int err = 0;
+ struct msm_gpio_chip *chip;
+ unsigned long irq_flags;
+ unsigned long chip_index;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip == NULL) {
+ err = -EINVAL;
+ goto err;
+ }
+ chip_index = gpio - chip->start;
+ if (chip->state[chip_index].refcount == 0) {
+ chip->configure(chip, gpio, flags);
+ chip->state[chip_index].flags = flags;
+ chip->state[chip_index].refcount++;
+ } else if ((flags & IRQF_SHARED) && (chip->state[chip_index].flags & IRQF_SHARED))
+ chip->state[chip_index].refcount++;
+ else
+ err = -EBUSY;
+err:
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ return err;
+}
+
+int gpio_request(unsigned gpio, const char *label)
+{
+ return request_gpio(gpio, 0);
+}
+EXPORT_SYMBOL(gpio_request);
+
+void gpio_free(unsigned gpio)
+{
+ struct msm_gpio_chip *chip;
+ unsigned long irq_flags;
+ unsigned long chip_index;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip) {
+ chip_index = gpio - chip->start;
+ chip->state[chip_index].refcount--;
+ }
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+}
+EXPORT_SYMBOL(gpio_free);
+
+static int gpio_get_irq_num(unsigned int gpio, unsigned int *irqp, unsigned long *irqnumflagsp)
+{
+ int ret = -ENOTSUPP;
+ struct msm_gpio_chip *chip;
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip && chip->get_irq_num)
+ ret = chip->get_irq_num(chip, gpio, irqp, irqnumflagsp);
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ return ret;
+}
+
+int gpio_to_irq(unsigned gpio)
+{
+ int ret, irq;
+ ret = gpio_get_irq_num(gpio, &irq, NULL);
+ if (ret)
+ return ret;
+ return irq;
+}
+EXPORT_SYMBOL(gpio_to_irq);
+
+int gpio_configure(unsigned int gpio, unsigned long flags)
+{
+ int ret = -ENOTSUPP;
+ struct msm_gpio_chip *chip;
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip)
+ ret = chip->configure(chip, gpio, flags);
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ return ret;
+}
+EXPORT_SYMBOL(gpio_configure);
+
+int gpio_direction_input(unsigned gpio)
+{
+ return gpio_configure(gpio, GPIOF_INPUT);
+}
+EXPORT_SYMBOL(gpio_direction_input);
+
+int gpio_direction_output(unsigned gpio, int value)
+{
+ gpio_set_value(gpio, value);
+ return gpio_configure(gpio, GPIOF_DRIVE_OUTPUT);
+}
+EXPORT_SYMBOL(gpio_direction_output);
+
+int gpio_get_value(unsigned gpio)
+{
+ int ret = -ENOTSUPP;
+ struct msm_gpio_chip *chip;
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip && chip->read)
+ ret = chip->read(chip, gpio);
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ return ret;
+}
+EXPORT_SYMBOL(gpio_get_value);
+
+void gpio_set_value(unsigned gpio, int on)
+{
+ int ret = -ENOTSUPP;
+ struct msm_gpio_chip *chip;
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip && chip->write)
+ ret = chip->write(chip, gpio, on);
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+}
+EXPORT_SYMBOL(gpio_set_value);
+
+int gpio_read_detect_status(unsigned int gpio)
+{
+ int ret = -ENOTSUPP;
+ struct msm_gpio_chip *chip;
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip && chip->read_detect_status)
+ ret = chip->read_detect_status(chip, gpio);
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ return ret;
+}
+EXPORT_SYMBOL(gpio_read_detect_status);
+
+int gpio_clear_detect_status(unsigned int gpio)
+{
+ int ret = -ENOTSUPP;
+ struct msm_gpio_chip *chip;
+ unsigned long irq_flags;
+
+ spin_lock_irqsave(&gpio_chips_lock, irq_flags);
+ chip = get_gpio_chip_locked(gpio);
+ if (chip && chip->clear_detect_status)
+ ret = chip->clear_detect_status(chip, gpio);
+ spin_unlock_irqrestore(&gpio_chips_lock, irq_flags);
+ return ret;
+}
+EXPORT_SYMBOL(gpio_clear_detect_status);
diff --git a/arch/arm/mach-msm/gpio_chip.h b/arch/arm/mach-msm/gpio_chip.h
new file mode 100644
index 0000000..1158b96
--- /dev/null
+++ b/arch/arm/mach-msm/gpio_chip.h
@@ -0,0 +1,50 @@
+/* arch/arm/mach-msm/gpio_chip.h
+ *
+ * Copyright (C) 2007 Google, Inc.
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that 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.
+ *
+ */
+
+#ifndef _LINUX_GPIO_CHIP_H
+#define _LINUX_GPIO_CHIP_H
+
+#include <linux/list.h>
+
+struct msm_gpio_chip {
+ struct list_head list;
+ struct gpio_state *state;
+
+ unsigned int start;
+ unsigned int end;
+
+ int (*configure)(struct msm_gpio_chip *chip, unsigned int gpio, unsigned long flags);
+ int (*get_irq_num)(struct msm_gpio_chip *chip, unsigned int gpio, unsigned int *irqp, unsigned long *irqnumflagsp);
+ int (*read)(struct msm_gpio_chip *chip, unsigned int gpio);
+ int (*write)(struct msm_gpio_chip *chip, unsigned int gpio, unsigned on);
+ int (*read_detect_status)(struct msm_gpio_chip *chip, unsigned int gpio);
+ int (*clear_detect_status)(struct msm_gpio_chip *chip, unsigned int gpio);
+};
+
+int register_msm_gpio_chip(struct msm_gpio_chip *gpio_chip);
+
+/* extended gpio api */
+
+#define GPIOF_IRQF_MASK 0x0000ffff /* use to specify edge detection without */
+#define GPIOF_IRQF_TRIGGER_NONE 0x00010000 /* IRQF_TRIGGER_NONE is 0 which also means "as already configured" */
+#define GPIOF_INPUT 0x00020000
+#define GPIOF_DRIVE_OUTPUT 0x00040000
+#define GPIOF_OUTPUT_LOW 0x00080000
+#define GPIOF_OUTPUT_HIGH 0x00100000
+
+#define GPIOIRQF_SHARED 0x00000001 /* the irq line is shared with other inputs */
+
+
+#endif
diff --git a/arch/arm/mach-msm/include/mach/gpio.h b/arch/arm/mach-msm/include/mach/gpio.h
new file mode 100644
index 0000000..92ce18d
--- /dev/null
+++ b/arch/arm/mach-msm/include/mach/gpio.h
@@ -0,0 +1,36 @@
+/* linux/include/asm-arm/arch-msm/gpio.h
+ *
+ * Copyright (C) 2007 Google, Inc.
+ * Author: Mike Lockwood <[email protected]>
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that 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.
+ *
+ */
+
+#ifndef __ASM_ARCH_MSM_GPIO_H
+#define __ASM_ARCH_MSM_GPIO_H
+
+#include <linux/interrupt.h>
+
+int gpio_request(unsigned gpio, const char *label);
+void gpio_free(unsigned gpio);
+int gpio_direction_input(unsigned gpio);
+int gpio_direction_output(unsigned gpio, int value);
+int gpio_get_value(unsigned gpio);
+void gpio_set_value(unsigned gpio, int value);
+int gpio_to_irq(unsigned gpio);
+
+#include <asm-generic/gpio.h>
+
+extern int gpio_configure(unsigned int gpio, unsigned long flags);
+extern int gpio_read_detect_status(unsigned int gpio);
+extern int gpio_clear_detect_status(unsigned int gpio);
+
+#endif


--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-10 17:41:31

by Mark Brown

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Thu, Dec 10, 2009 at 06:24:58PM +0100, Pavel Machek wrote:

> > Further to this, I think it is worth doing the work to make this gpiolib
> > now. Most of the other ARM chips now support gpiolib, so it would seem a
> > bit of a step backwards to start adding new chips which don't. I think
> > that adding the gpiolib support will also cleanup the mess that is
> > register_gpio_chip, since this is all already handled by the gpiolib core.

> I tried going through drivers/gpio/gpiolib.c and it seems to be a lot
> of code -- mostly sysrq interface to userland. I'm not sure how much
> code could be shared...

Everything in generic_gpio.c could easily be shared, which also gives
you all the standard APIs drivers and userspace expect without having to
reimplement them or ending up with slightly incompatible implementations.

2009-12-10 19:48:36

by Ryan Mallon

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

Pavel Machek wrote:
> Hi!
>
>>> This is still really screwy. Why are you creating your own version of
>>> struct gpio_chip in addition to the one in include/asm-generic/gpio.h
>>> (which you also appear to include in some places). It makes the code
>>> extremely confusing. Other architectures use wrapper structures. Can you
>>> have something like this instead:
>>>
>>> struct dream_gpio_chip {
>>> struct gpio_chip chip;
>>>
>>> /* Dream specific bits */
>>> };
>>>
>>> The name of this function also needs to be changed to something less
>>> generic since it is being exported globally.
>>>
>>> I also think this function is doing way to much work for what it is.
>>> Does it really need to be this complicated?
>> Further to this, I think it is worth doing the work to make this gpiolib
>> now. Most of the other ARM chips now support gpiolib, so it would seem a
>> bit of a step backwards to start adding new chips which don't. I think
>> that adding the gpiolib support will also cleanup the mess that is
>> register_gpio_chip, since this is all already handled by the gpiolib core.
>
> I tried going through drivers/gpio/gpiolib.c and it seems to be a lot
> of code -- mostly sysrq interface to userland. I'm not sure how much
> code could be shared...

Its not much work to go from generic gpio (which you have now) to
gpiolib, and in the end it will make the code simpler, more extensible,
you get sysfs access for free, etc. You will need to wrap up your
gpio_chip struct as I suggested:

struct msm_gpio_chip {
struct gpio_chip;

/* MSM/Dream/Trout(?) bits */
};
#define to_msm_gpio_chip(c, container_of(c, struct msm_gpio_chip, chip)

As an aside, I don't quite understand the naming conventions here. Is
the gpio stuff generic to the MSM chip, or specific to the Dream/Trout
board? It would be good if the gpio implementation could be completely
generic to the chip, and all the board specific bits be kept in the
board specific files.

You gpio_set, get, direction, etc functions become static:

static gpio_set_value(struct gpio_chip *chip, unsigned offset, int val)
{
struct msm_gpio_chip *msm_chip = to_msm_gpio_chip(chip);

...
}

and you have a descriptor for your chip (or an array of these if you
want multiple banks of gpios):

static struct msm_gpios = {
.chip = {
.label = "msm_gpio",
.set = gpio_set_value,
...
},
/* MSM specific bits */
};

void __init msm_init_gpio(void)
{
gpiochip_add(&msm_gpios);

/* Other setup, gpio irqs, etc */
}

Your msm_register_gpio_chip function should disappear and your
gpio_request and gpio_free functions can either be removed, or at least
become much simpler since gpiolib already handles most of what those
functions are doing.

Have a look at the other ARM chips which have gpiolib support for a
guide. The ep93xx and at91 ones which I did are reasonably simple to
follow, and also demonstrate how to use the debugfs hooks which you may
find useful. Also look at Documentation/gpio.txt which has some more
detailed information on gpiolib.

~Ryan

--
Bluewater Systems Ltd - ARM Technology Solution Centre

Ryan Mallon 5 Amuri Park, 404 Barbadoes St
[email protected] PO Box 13 889, Christchurch 8013
http://www.bluewatersys.com New Zealand
Phone: +64 3 3779127 Freecall: Australia 1800 148 751
Fax: +64 3 3779135 USA 1800 261 2934

2009-12-10 23:14:10

by Hartley Sweeten

[permalink] [raw]
Subject: RE: GPIO support for HTC Dream

On Thursday, December 10, 2009 12:49 PM, Ryan Mallon wrote:
> Pavel Machek wrote:
>> Hi!
>>
>>>> This is still really screwy. Why are you creating your own version of
>>>> struct gpio_chip in addition to the one in include/asm-generic/gpio.h
>>>> (which you also appear to include in some places). It makes the code
>>>> extremely confusing. Other architectures use wrapper structures. Can you
>>>> have something like this instead:
>>>>
>>>> struct dream_gpio_chip {
>>>> struct gpio_chip chip;
>>>>
>>>> /* Dream specific bits */
>>>> };
>>>>
>>>> The name of this function also needs to be changed to something less
>>>> generic since it is being exported globally.
>>>>
>>>> I also think this function is doing way to much work for what it is.
>>>> Does it really need to be this complicated?
>>> Further to this, I think it is worth doing the work to make this gpiolib
>>> now. Most of the other ARM chips now support gpiolib, so it would seem a
>>> bit of a step backwards to start adding new chips which don't. I think
>>> that adding the gpiolib support will also cleanup the mess that is
>>> register_gpio_chip, since this is all already handled by the gpiolib core.
>>
>> I tried going through drivers/gpio/gpiolib.c and it seems to be a lot
>> of code -- mostly sysrq interface to userland. I'm not sure how much
>> code could be shared...
>
> Its not much work to go from generic gpio (which you have now) to
> gpiolib, and in the end it will make the code simpler, more extensible,
> you get sysfs access for free, etc. You will need to wrap up your
> gpio_chip struct as I suggested:
>
> struct msm_gpio_chip {
> struct gpio_chip;
>
> /* MSM/Dream/Trout(?) bits */
> };
> #define to_msm_gpio_chip(c, container_of(c, struct msm_gpio_chip, chip)
>
> As an aside, I don't quite understand the naming conventions here. Is
> the gpio stuff generic to the MSM chip, or specific to the Dream/Trout
> board? It would be good if the gpio implementation could be completely
> generic to the chip, and all the board specific bits be kept in the
> board specific files.
>
> You gpio_set, get, direction, etc functions become static:
>
> static gpio_set_value(struct gpio_chip *chip, unsigned offset, int val)
> {
> struct msm_gpio_chip *msm_chip = to_msm_gpio_chip(chip);
>
> ...
> }
>
> and you have a descriptor for your chip (or an array of these if you
> want multiple banks of gpios):
>
> static struct msm_gpios = {
> .chip = {
> .label = "msm_gpio",
> .set = gpio_set_value,
> ...
> },
> /* MSM specific bits */
> };
>
> void __init msm_init_gpio(void)
> {
> gpiochip_add(&msm_gpios);
>
> /* Other setup, gpio irqs, etc */
> }
>
> Your msm_register_gpio_chip function should disappear and your
> gpio_request and gpio_free functions can either be removed, or at least
> become much simpler since gpiolib already handles most of what those
> functions are doing.
>
> Have a look at the other ARM chips which have gpiolib support for a
> guide. The ep93xx and at91 ones which I did are reasonably simple to
> follow, and also demonstrate how to use the debugfs hooks which you may
> find useful. Also look at Documentation/gpio.txt which has some more
> detailed information on gpiolib.

As Ryan says, using gpiolib will clean this up immensely.

It appears the what you really have for gpio's is 7 8-bit ports that start
with gpio number 128. Each port appears to only have one control register.
This register is written with a '1' to drive the gpio as a high output and
'0' to drive it as a low output or to use it as an input. Not really
sure if this is correct since the code is a bit screwy.

Your current code is written so that all of the gpio's are in one "chip".
Because of this you are having to calculate the 'reg' needed to access the
gpio whenever you need to read or write to a gpio.

If you follow the ep93xx implementation you can break the whole thing down
into 'banks' and simplify everything. Something like:



struct dream_gpio_chip {
struct gpio_chip chip;

void __iomem *reg;
};

#define to_dream_gpio_chip(c) container_of(c, struct dream_gpio_chip, chip)


#define DREAM_GPIO_BANK(name, reg, base_gpio) \
{ \
.chip = { \
.label = name, \
.direction_input = dream_gpio_direction_input, \
.direction_output = dream_gpio_direction_output, \
.get = dream_gpio_get, \
.set = dream_gpio_set, \
.dbg_show = dream_gpio_dbg_show, \
.base = base_gpio, \
.ngpio = 8, \
}, \
.reg = DREAM_CPLD_BASE + reg, \
}

static struct dream_gpio_chip dream_gpio_banks[] = {
DREAM_GPIO_BANK("MISC2", 0x00, DREAM_GPIO_MISC2_BASE),
DREAM_GPIO_BANK("MISC3", 0x02, DREAM_GPIO_MISC3_BASE),
DREAM_GPIO_BANK("MISC4", 0x04, DREAM_GPIO_MISC4_BASE),
DREAM_GPIO_BANK("MISC5", 0x06, DREAM_GPIO_MISC5_BASE),
DREAM_GPIO_BANK("INT2", 0x08, DREAM_GPIO_INT2_BASE),
DREAM_GPIO_BANK("MISC1", 0x0a, DREAM_GPIO_MISC1_BASE),
DREAM_GPIO_BANK("VIRTUAL", 0x12, DREAM_GPIO_VIRTUAL_BASE),
};

void __init dream_gpio_init(void)
{
int i;

for (i = 0; i < ARRAY_SIZE(dream_gpio_banks); i++)
gpiochip_add(&dream_gpio_banks[i].chip);
}


With this you can now just access the dream_gpio_chip data in all
the member function using the to_dream_gpio_chip() macro.

I agree with Ryan and think you would be better off in the long
run to re-code this and use gpiolib. You might also want to break
out all the gpio interrupt stuff and submit it as a seperate patch.

Regards,
Hartley

2009-12-11 19:58:27

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

Hi!

> With this you can now just access the dream_gpio_chip data in all
> the member function using the to_dream_gpio_chip() macro.
>
> I agree with Ryan and think you would be better off in the long
> run to re-code this and use gpiolib. You might also want to break
> out all the gpio interrupt stuff and submit it as a seperate patch.

Yep, lets ignore the interrupts, I do not need them for led blinking
:-).

And... thanks!
Pavel

--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-11 22:12:20

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

Hi!

Ok, thanks to Ryan and everyone... You were right, the code was way
too complex.

Cleaning it up according to Hartley's great howto resulted in:

arch/arm/Kconfig | 1
arch/arm/mach-msm/board-dream-gpio.c | 327 +++++++++--------------------------
arch/arm/mach-msm/board-dream.c | 24 --
arch/arm/mach-msm/generic_gpio.c | 270 ----------------------------
arch/arm/mach-msm/gpio_chip.h | 30 ---
kernel/printk.c | 6
6 files changed, 102 insertions(+), 556 deletions(-)

> As Ryan says, using gpiolib will clean this up immensely.
>
> It appears the what you really have for gpio's is 7 8-bit ports that start
> with gpio number 128. Each port appears to only have one control register.
> This register is written with a '1' to drive the gpio as a high output and
> '0' to drive it as a low output or to use it as an input. Not really
> sure if this is correct since the code is a bit screwy.

It seems it is, because it seems to work.

> Your current code is written so that all of the gpio's are in one "chip".
> Because of this you are having to calculate the 'reg' needed to access the
> gpio whenever you need to read or write to a gpio.
>
> If you follow the ep93xx implementation you can break the whole thing down
> into 'banks' and simplify everything. Something like:

...and get 100 lines of results, instead of 600... Yep, thanks.

Now, it will still need some cleanups -- I'm not sure if gpios are
dream-specific or generic for whole msm.... I kind of assume they
should be generic for msm. Google people, can you help?

> static struct dream_gpio_chip dream_gpio_banks[] = {
> DREAM_GPIO_BANK("MISC2", 0x00, DREAM_GPIO_MISC2_BASE),
> DREAM_GPIO_BANK("MISC3", 0x02, DREAM_GPIO_MISC3_BASE),
> DREAM_GPIO_BANK("MISC4", 0x04, DREAM_GPIO_MISC4_BASE),
> DREAM_GPIO_BANK("MISC5", 0x06, DREAM_GPIO_MISC5_BASE),
> DREAM_GPIO_BANK("INT2", 0x08, DREAM_GPIO_INT2_BASE),
> DREAM_GPIO_BANK("MISC1", 0x0a, DREAM_GPIO_MISC1_BASE),
> DREAM_GPIO_BANK("VIRTUAL", 0x12, DREAM_GPIO_VIRTUAL_BASE),
> };

Yep, that did the trick.

> With this you can now just access the dream_gpio_chip data in all
> the member function using the to_dream_gpio_chip() macro.
>
> I agree with Ryan and think you would be better off in the long
> run to re-code this and use gpiolib. You might also want to break
> out all the gpio interrupt stuff and submit it as a seperate patch.

Will do. Here's how the patch looks now.

diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig
index 1c4119c..8bb8546 100644
--- a/arch/arm/Kconfig
+++ b/arch/arm/Kconfig
@@ -565,6 +565,8 @@ config ARCH_MSM
select CPU_V6
select GENERIC_TIME
select GENERIC_CLOCKEVENTS
+ select GENERIC_GPIO
+ select ARCH_REQUIRE_GPIOLIB
help
Support for Qualcomm MSM7K based systems. This runs on the ARM11
apps processor of the MSM7K and depends on a shared memory
diff --git a/arch/arm/mach-msm/Makefile b/arch/arm/mach-msm/Makefile
index 91e6f5c..4c2567e 100644
--- a/arch/arm/mach-msm/Makefile
+++ b/arch/arm/mach-msm/Makefile
@@ -6,4 +6,4 @@ obj-y += clock.o clock-7x01a.o

obj-$(CONFIG_MACH_HALIBUT) += board-halibut.o

-obj-$(CONFIG_MACH_TROUT) += board-dream.o
+obj-$(CONFIG_MACH_TROUT) += board-dream.o board-dream-gpio.o generic_gpio.o
diff --git a/arch/arm/mach-msm/board-dream-gpio.c b/arch/arm/mach-msm/board-dream-gpio.c
new file mode 100644
index 0000000..d90b8f9
--- /dev/null
+++ b/arch/arm/mach-msm/board-dream-gpio.c
@@ -0,0 +1,135 @@
+/*
+ * linux/arch/arm/mach-msm/gpio.c
+ *
+ * Copyright (C) 2005 HP Labs
+ * Copyright (C) 2008 Google, Inc.
+ * Copyright (C) 2009 Pavel Machek <[email protected]>
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ */
+
+#include <linux/clk.h>
+#include <linux/errno.h>
+#include <linux/interrupt.h>
+#include <linux/irq.h>
+#include <linux/debugfs.h>
+#include <linux/seq_file.h>
+#include <linux/kernel.h>
+#include <linux/list.h>
+#include <linux/module.h>
+#include <linux/io.h>
+#include <linux/gpio.h>
+
+#include <mach/hardware.h>
+#include <mach/gpio.h>
+
+#include <asm/gpio.h>
+
+#include "board-dream.h"
+
+struct msm_gpio_chip {
+ struct gpio_chip chip;
+ void __iomem *reg; /* Base of register bank */
+ u8 shadow;
+};
+
+#define to_msm_gpio_chip(c) container_of(c, struct msm_gpio_chip, chip)
+
+static void msm_gpiolib_set(struct gpio_chip *chip, unsigned offset, int val);
+static int msm_gpiolib_get(struct gpio_chip *chip, unsigned offset);
+static int msm_gpiolib_direction_output(struct gpio_chip *chip,
+ unsigned offset, int val);
+static int msm_gpiolib_direction_input(struct gpio_chip *chip,
+ unsigned offset);
+
+#define DREAM_GPIO_BANK(name, reg_num, base_gpio, shadow_val) \
+ { \
+ .chip = { \
+ .label = name, \
+ .direction_input = msm_gpiolib_direction_input, \
+ .direction_output = msm_gpiolib_direction_output, \
+ .get = msm_gpiolib_get, \
+ .set = msm_gpiolib_set, \
+ .base = base_gpio, \
+ .ngpio = 8, \
+ }, \
+ .reg = reg_num + DREAM_CPLD_BASE, \
+ .shadow = shadow_val, \
+ }
+
+static struct msm_gpio_chip msm_gpio_banks[] = {
+#if defined(CONFIG_MSM_DEBUG_UART1)
+ /* H2W pins <-> UART1 */
+ DREAM_GPIO_BANK("MISC2", 0x00, DREAM_GPIO_MISC2_BASE, 0x40),
+#else
+ /* H2W pins <-> UART3, Bluetooth <-> UART1 */
+ DREAM_GPIO_BANK("MISC2", 0x00, DREAM_GPIO_MISC2_BASE, 0x80),
+#endif
+ /* I2C pull */
+ DREAM_GPIO_BANK("MISC3", 0x02, DREAM_GPIO_MISC3_BASE, 0x04),
+ DREAM_GPIO_BANK("MISC4", 0x04, DREAM_GPIO_MISC4_BASE, 0),
+ /* mmdi 32k en */
+ DREAM_GPIO_BANK("MISC5", 0x06, DREAM_GPIO_MISC5_BASE, 0x04),
+ DREAM_GPIO_BANK("INT2", 0x08, DREAM_GPIO_INT2_BASE, 0),
+ DREAM_GPIO_BANK("MISC1", 0x0a, DREAM_GPIO_MISC1_BASE, 0),
+ DREAM_GPIO_BANK("VIRTUAL", 0x12, DREAM_GPIO_VIRTUAL_BASE, 0),
+};
+
+static int msm_gpiolib_get(struct gpio_chip *chip, unsigned offset)
+{
+ struct msm_gpio_chip *msm_gpio = to_msm_gpio_chip(chip);
+ unsigned mask = 1 << offset;
+
+ return !! (readb(msm_gpio->reg) & mask);
+}
+
+static void msm_gpiolib_set(struct gpio_chip *chip, unsigned offset, int val)
+{
+ struct msm_gpio_chip *msm_gpio = to_msm_gpio_chip(chip);
+ unsigned mask = 1 << offset;
+
+ if (val)
+ msm_gpio->shadow |= mask;
+ else
+ msm_gpio->shadow &= ~mask;
+
+ writeb(msm_gpio->shadow, msm_gpio->reg);
+}
+
+static int msm_gpiolib_direction_input(struct gpio_chip *chip,
+ unsigned offset)
+{
+ msm_gpiolib_set(chip, offset, 0);
+ return 0;
+}
+
+static int msm_gpiolib_direction_output(struct gpio_chip *chip,
+ unsigned offset, int val)
+{
+ msm_gpiolib_set(chip, offset, val);
+ return 0;
+}
+
+int gpio_to_irq(unsigned gpio)
+{
+ BUG();
+}
+
+/*
+ * Called from the processor-specific init to enable GPIO pin support.
+ */
+int __init dream_init_gpio(void)
+{
+ int i;
+
+ for (i = 0; i < ARRAY_SIZE(msm_gpio_banks); i++)
+ gpiochip_add(&msm_gpio_banks[i].chip);
+
+ return 0;
+}
+
+postcore_initcall(dream_init_gpio);
+
diff --git a/arch/arm/mach-msm/board-dream.h b/arch/arm/mach-msm/board-dream.h
index 4f345a5..aab1faf 100644
--- a/arch/arm/mach-msm/board-dream.h
+++ b/arch/arm/mach-msm/board-dream.h
@@ -1,5 +1,153 @@

-#define TROUT_CPLD_BASE 0xE8100000
-#define TROUT_CPLD_START 0x98000000
-#define TROUT_CPLD_SIZE SZ_4K
+#define MSM_SMI_BASE 0x00000000
+#define MSM_SMI_SIZE 0x00800000

+#define MSM_EBI_BASE 0x10000000
+#define MSM_EBI_SIZE 0x06e00000
+
+#define MSM_PMEM_GPU0_BASE 0x00000000
+#define MSM_PMEM_GPU0_SIZE 0x00700000
+
+#define MSM_PMEM_MDP_BASE 0x02000000
+#define MSM_PMEM_MDP_SIZE 0x00800000
+
+#define MSM_PMEM_ADSP_BASE 0x02800000
+#define MSM_PMEM_ADSP_SIZE 0x00800000
+
+#define MSM_PMEM_CAMERA_BASE 0x03000000
+#define MSM_PMEM_CAMERA_SIZE 0x00800000
+
+#define MSM_FB_BASE 0x03800000
+#define MSM_FB_SIZE 0x00100000
+
+#define MSM_LINUX_BASE MSM_EBI_BASE
+#define MSM_LINUX_SIZE 0x06500000
+
+#define MSM_PMEM_GPU1_SIZE 0x800000
+#define MSM_PMEM_GPU1_BASE (MSM_RAM_CONSOLE_BASE - MSM_PMEM_GPU1_SIZE)
+
+#define MSM_RAM_CONSOLE_BASE (MSM_EBI_BASE + 0x6d00000)
+#define MSM_RAM_CONSOLE_SIZE (128 * SZ_1K)
+
+#if (MSM_FB_BASE + MSM_FB_SIZE) >= (MSM_PMEM_GPU1_BASE)
+#error invalid memory map
+#endif
+
+#define DECLARE_MSM_IOMAP
+#include <mach/msm_iomap.h>
+
+#define DREAM_4_BALL_UP_0 1
+#define DREAM_4_BALL_LEFT_0 18
+#define DREAM_4_BALL_DOWN_0 57
+#define DREAM_4_BALL_RIGHT_0 91
+
+#define DREAM_5_BALL_UP_0 94
+#define DREAM_5_BALL_LEFT_0 18
+#define DREAM_5_BALL_DOWN_0 90
+#define DREAM_5_BALL_RIGHT_0 19
+
+#define DREAM_POWER_KEY 20
+
+#define DREAM_4_TP_LS_EN 19
+#define DREAM_5_TP_LS_EN 1
+
+#define DREAM_CPLD_BASE 0xE8100000
+#define DREAM_CPLD_START 0x98000000
+#define DREAM_CPLD_SIZE SZ_4K
+
+#define DREAM_GPIO_CABLE_IN1 (83)
+#define DREAM_GPIO_CABLE_IN2 (49)
+
+#define DREAM_GPIO_START (128)
+
+#define DREAM_GPIO_INT_MASK0_REG (0x0c)
+#define DREAM_GPIO_INT_STAT0_REG (0x0e)
+#define DREAM_GPIO_INT_MASK1_REG (0x14)
+#define DREAM_GPIO_INT_STAT1_REG (0x10)
+
+#define DREAM_GPIO_HAPTIC_PWM (28)
+#define DREAM_GPIO_PS_HOLD (25)
+
+#define DREAM_GPIO_MISC2_BASE (DREAM_GPIO_START + 0x00)
+#define DREAM_GPIO_MISC3_BASE (DREAM_GPIO_START + 0x08)
+#define DREAM_GPIO_MISC4_BASE (DREAM_GPIO_START + 0x10)
+#define DREAM_GPIO_MISC5_BASE (DREAM_GPIO_START + 0x18)
+#define DREAM_GPIO_INT2_BASE (DREAM_GPIO_START + 0x20)
+#define DREAM_GPIO_MISC1_BASE (DREAM_GPIO_START + 0x28)
+#define DREAM_GPIO_VIRTUAL_BASE (DREAM_GPIO_START + 0x30)
+#define DREAM_GPIO_INT5_BASE (DREAM_GPIO_START + 0x48)
+
+#define DREAM_GPIO_CHARGER_EN (DREAM_GPIO_MISC2_BASE + 0)
+#define DREAM_GPIO_ISET (DREAM_GPIO_MISC2_BASE + 1)
+#define DREAM_GPIO_H2W_DAT_DIR (DREAM_GPIO_MISC2_BASE + 2)
+#define DREAM_GPIO_H2W_CLK_DIR (DREAM_GPIO_MISC2_BASE + 3)
+#define DREAM_GPIO_H2W_DAT_GPO (DREAM_GPIO_MISC2_BASE + 4)
+#define DREAM_GPIO_H2W_CLK_GPO (DREAM_GPIO_MISC2_BASE + 5)
+#define DREAM_GPIO_H2W_SEL0 (DREAM_GPIO_MISC2_BASE + 6)
+#define DREAM_GPIO_H2W_SEL1 (DREAM_GPIO_MISC2_BASE + 7)
+
+#define DREAM_GPIO_SPOTLIGHT_EN (DREAM_GPIO_MISC3_BASE + 0)
+#define DREAM_GPIO_FLASH_EN (DREAM_GPIO_MISC3_BASE + 1)
+#define DREAM_GPIO_I2C_PULL (DREAM_GPIO_MISC3_BASE + 2)
+#define DREAM_GPIO_TP_I2C_PULL (DREAM_GPIO_MISC3_BASE + 3)
+#define DREAM_GPIO_TP_EN (DREAM_GPIO_MISC3_BASE + 4)
+#define DREAM_GPIO_JOG_EN (DREAM_GPIO_MISC3_BASE + 5)
+#define DREAM_GPIO_UI_LED_EN (DREAM_GPIO_MISC3_BASE + 6)
+#define DREAM_GPIO_QTKEY_LED_EN (DREAM_GPIO_MISC3_BASE + 7)
+
+#define DREAM_GPIO_VCM_PWDN (DREAM_GPIO_MISC4_BASE + 0)
+#define DREAM_GPIO_USB_H2W_SW (DREAM_GPIO_MISC4_BASE + 1)
+#define DREAM_GPIO_COMPASS_RST_N (DREAM_GPIO_MISC4_BASE + 2)
+#define DREAM_GPIO_HAPTIC_EN_UP (DREAM_GPIO_MISC4_BASE + 3)
+#define DREAM_GPIO_HAPTIC_EN_MAIN (DREAM_GPIO_MISC4_BASE + 4)
+#define DREAM_GPIO_USB_PHY_RST_N (DREAM_GPIO_MISC4_BASE + 5)
+#define DREAM_GPIO_WIFI_PA_RESETX (DREAM_GPIO_MISC4_BASE + 6)
+#define DREAM_GPIO_WIFI_EN (DREAM_GPIO_MISC4_BASE + 7)
+
+#define DREAM_GPIO_BT_32K_EN (DREAM_GPIO_MISC5_BASE + 0)
+#define DREAM_GPIO_MAC_32K_EN (DREAM_GPIO_MISC5_BASE + 1)
+#define DREAM_GPIO_MDDI_32K_EN (DREAM_GPIO_MISC5_BASE + 2)
+#define DREAM_GPIO_COMPASS_32K_EN (DREAM_GPIO_MISC5_BASE + 3)
+
+#define DREAM_GPIO_NAVI_ACT_N (DREAM_GPIO_INT2_BASE + 0)
+#define DREAM_GPIO_COMPASS_IRQ (DREAM_GPIO_INT2_BASE + 1)
+#define DREAM_GPIO_SLIDING_DET (DREAM_GPIO_INT2_BASE + 2)
+#define DREAM_GPIO_AUD_HSMIC_DET_N (DREAM_GPIO_INT2_BASE + 3)
+#define DREAM_GPIO_SD_DOOR_N (DREAM_GPIO_INT2_BASE + 4)
+#define DREAM_GPIO_CAM_BTN_STEP1_N (DREAM_GPIO_INT2_BASE + 5)
+#define DREAM_GPIO_CAM_BTN_STEP2_N (DREAM_GPIO_INT2_BASE + 6)
+#define DREAM_GPIO_TP_ATT_N (DREAM_GPIO_INT2_BASE + 7)
+#define DREAM_GPIO_BANK0_FIRST_INT_SOURCE (DREAM_GPIO_NAVI_ACT_N)
+#define DREAM_GPIO_BANK0_LAST_INT_SOURCE (DREAM_GPIO_TP_ATT_N)
+
+#define DREAM_GPIO_H2W_DAT_GPI (DREAM_GPIO_MISC1_BASE + 0)
+#define DREAM_GPIO_H2W_CLK_GPI (DREAM_GPIO_MISC1_BASE + 1)
+#define DREAM_GPIO_CPLD128_VER_0 (DREAM_GPIO_MISC1_BASE + 4)
+#define DREAM_GPIO_CPLD128_VER_1 (DREAM_GPIO_MISC1_BASE + 5)
+#define DREAM_GPIO_CPLD128_VER_2 (DREAM_GPIO_MISC1_BASE + 6)
+#define DREAM_GPIO_CPLD128_VER_3 (DREAM_GPIO_MISC1_BASE + 7)
+
+#define DREAM_GPIO_SDMC_CD_N (DREAM_GPIO_VIRTUAL_BASE + 0)
+#define DREAM_GPIO_END (DREAM_GPIO_SDMC_CD_N)
+#define DREAM_GPIO_BANK1_FIRST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
+#define DREAM_GPIO_BANK1_LAST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
+
+#define DREAM_GPIO_VIRTUAL_TO_REAL_OFFSET \
+ (DREAM_GPIO_INT5_BASE - DREAM_GPIO_VIRTUAL_BASE)
+
+#define DREAM_INT_START (NR_MSM_IRQS + NR_GPIO_IRQS)
+#define DREAM_INT_BANK0_COUNT (8)
+#define DREAM_INT_BANK1_START (DREAM_INT_START + DREAM_INT_BANK0_COUNT)
+#define DREAM_INT_BANK1_COUNT (1)
+#define DREAM_INT_END (DREAM_INT_START + DREAM_INT_BANK0_COUNT + \
+ DREAM_INT_BANK1_COUNT - 1)
+#define DREAM_GPIO_TO_INT(n) (((n) <= DREAM_GPIO_BANK0_LAST_INT_SOURCE) ? \
+ (DREAM_INT_START - DREAM_GPIO_BANK0_FIRST_INT_SOURCE + (n)) : \
+ (DREAM_INT_BANK1_START - DREAM_GPIO_BANK1_FIRST_INT_SOURCE + (n)))
+
+#define DREAM_INT_TO_BANK(n) ((n - DREAM_INT_START) / DREAM_INT_BANK0_COUNT)
+#define DREAM_INT_TO_MASK(n) (1U << ((n - DREAM_INT_START) & 7))
+#define DREAM_BANK_TO_MASK_REG(bank) \
+ (bank ? DREAM_GPIO_INT_MASK1_REG : DREAM_GPIO_INT_MASK0_REG)
+#define DREAM_BANK_TO_STAT_REG(bank) \
+ (bank ? DREAM_GPIO_INT_STAT1_REG : DREAM_GPIO_INT_STAT0_REG)
diff --git a/arch/arm/mach-msm/include/mach/gpio.h b/arch/arm/mach-msm/include/mach/gpio.h
new file mode 100644
index 0000000..92ce18d
--- /dev/null
+++ b/arch/arm/mach-msm/include/mach/gpio.h
@@ -0,0 +1,36 @@
+/* linux/include/asm-arm/arch-msm/gpio.h
+ *
+ * Copyright (C) 2007 Google, Inc.
+ * Author: Mike Lockwood <[email protected]>
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that 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.
+ *
+ */
+
+#ifndef __ASM_ARCH_MSM_GPIO_H
+#define __ASM_ARCH_MSM_GPIO_H
+
+#include <linux/interrupt.h>
+
+int gpio_request(unsigned gpio, const char *label);
+void gpio_free(unsigned gpio);
+int gpio_direction_input(unsigned gpio);
+int gpio_direction_output(unsigned gpio, int value);
+int gpio_get_value(unsigned gpio);
+void gpio_set_value(unsigned gpio, int value);
+int gpio_to_irq(unsigned gpio);
+
+#include <asm-generic/gpio.h>
+
+extern int gpio_configure(unsigned int gpio, unsigned long flags);
+extern int gpio_read_detect_status(unsigned int gpio);
+extern int gpio_clear_detect_status(unsigned int gpio);
+
+#endif

--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-11 22:40:37

by Arve Hjønnevåg

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Fri, Dec 11, 2009 at 2:10 PM, Pavel Machek <[email protected]> wrote:
> Hi!
>
> Ok, thanks to Ryan and everyone... You were right, the code was way
> too complex.
>
> Cleaning it up according to Hartley's great howto resulted in:
>
> ?arch/arm/Kconfig ? ? ? ? ? ? ? ? ? ? | ? ?1
> ?arch/arm/mach-msm/board-dream-gpio.c | ?327 +++++++++--------------------------
> ?arch/arm/mach-msm/board-dream.c ? ? ?| ? 24 --
> ?arch/arm/mach-msm/generic_gpio.c ? ? | ?270 ----------------------------
> ?arch/arm/mach-msm/gpio_chip.h ? ? ? ?| ? 30 ---
> ?kernel/printk.c ? ? ? ? ? ? ? ? ? ? ?| ? ?6
> ?6 files changed, 102 insertions(+), 556 deletions(-)
>
>> As Ryan says, using gpiolib will clean this up immensely.
>>
>> It appears the what you really have for gpio's is 7 8-bit ports that start
>> with gpio number 128. ?Each port appears to only have one control register.
>> This register is written with a '1' to drive the gpio as a high output and
>> '0' to drive it as a low output or to use it as an input. ?Not really
>> sure if this is correct since the code is a bit screwy.
>
> It seems it is, because it seems to work.
>
>> Your current code is written so that all of the gpio's are in one "chip".
>> Because of this you are having to calculate the 'reg' needed to access the
>> gpio whenever you need to read or write to a gpio.
>>
>> If you follow the ep93xx implementation you can break the whole thing down
>> into 'banks' and simplify everything. ?Something like:
>
> ...and get 100 lines of results, instead of 600... Yep, thanks.
>
> Now, it will still need some cleanups -- I'm not sure if gpios are
> dream-specific or generic for whole msm.... I kind of assume they
> should be generic for msm. Google people, can you help?

I'm not exactly sure what you are asking. Gpios in general are not
dream specific, the code in board-dream-gpio.c is. Some gpios (e.g.
DREAM_4_BALL_UP_0) are used for a dream specific function, but point
to a gpio that is generic to the msm architecture.

>
>> static struct dream_gpio_chip dream_gpio_banks[] = {
>> ? ? ? DREAM_GPIO_BANK("MISC2", 0x00, DREAM_GPIO_MISC2_BASE),
>> ? ? ? DREAM_GPIO_BANK("MISC3", 0x02, DREAM_GPIO_MISC3_BASE),
>> ? ? ? DREAM_GPIO_BANK("MISC4", 0x04, DREAM_GPIO_MISC4_BASE),
>> ? ? ? DREAM_GPIO_BANK("MISC5", 0x06, DREAM_GPIO_MISC5_BASE),
>> ? ? ? DREAM_GPIO_BANK("INT2", 0x08, DREAM_GPIO_INT2_BASE),
>> ? ? ? DREAM_GPIO_BANK("MISC1", 0x0a, DREAM_GPIO_MISC1_BASE),
>> ? ? ? DREAM_GPIO_BANK("VIRTUAL", 0x12, DREAM_GPIO_VIRTUAL_BASE),
>> };
>
> Yep, that did the trick.
>
>> With this you can now just access the dream_gpio_chip data in all
>> the member function using the to_dream_gpio_chip() macro.
>>
>> I agree with Ryan and think you would be better off in the long
>> run to re-code this and use gpiolib. ?You might also want to break
>> out all the gpio interrupt stuff and submit it as a seperate patch.
>
> Will do. Here's how the patch looks now.
>
> diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig
> index 1c4119c..8bb8546 100644
> --- a/arch/arm/Kconfig
> +++ b/arch/arm/Kconfig
> @@ -565,6 +565,8 @@ config ARCH_MSM
> ? ? ? ?select CPU_V6
> ? ? ? ?select GENERIC_TIME
> ? ? ? ?select GENERIC_CLOCKEVENTS
> + ? ? ? select GENERIC_GPIO
> + ? ? ? select ARCH_REQUIRE_GPIOLIB

Please do not do this in a board specific change. You have not changed
the msm generic gpio support to use gpiolib.

--
Arve Hj?nnev?g

2009-12-11 23:04:07

by Hartley Sweeten

[permalink] [raw]
Subject: RE: GPIO support for HTC Dream

On Friday, December 11, 2009 3:10 PM, Pavel Machek wrote:
> Hi!
>
> Ok, thanks to Ryan and everyone... You were right, the code was way
> too complex.

This looks MUCH better!

>
> Cleaning it up according to Hartley's great howto resulted in:

Glad to help. Couple of comments follow...

> arch/arm/Kconfig | 1
> arch/arm/mach-msm/board-dream-gpio.c | 327 +++++++++--------------------------
> arch/arm/mach-msm/board-dream.c | 24 --
> arch/arm/mach-msm/generic_gpio.c | 270 ----------------------------
> arch/arm/mach-msm/gpio_chip.h | 30 ---
> kernel/printk.c | 6
> 6 files changed, 102 insertions(+), 556 deletions(-)

Please update (or remove) this diffstat. It no longer matches the patch.

>> As Ryan says, using gpiolib will clean this up immensely.
>>
>> It appears the what you really have for gpio's is 7 8-bit ports that start
>> with gpio number 128. Each port appears to only have one control register.
>> This register is written with a '1' to drive the gpio as a high output and
>> '0' to drive it as a low output or to use it as an input. Not really
>> sure if this is correct since the code is a bit screwy.
>
> It seems it is, because it seems to work.

Ok. The hardware still seems a bit strange. Is there any datasheet available?

>> Your current code is written so that all of the gpio's are in one "chip".
>> Because of this you are having to calculate the 'reg' needed to access the
>> gpio whenever you need to read or write to a gpio.
>>
>> If you follow the ep93xx implementation you can break the whole thing down
>> into 'banks' and simplify everything. Something like:
>
> ...and get 100 lines of results, instead of 600... Yep, thanks.
>
> Now, it will still need some cleanups -- I'm not sure if gpios are
> dream-specific or generic for whole msm.... I kind of assume they
> should be generic for msm. Google people, can you help?
>
>> static struct dream_gpio_chip dream_gpio_banks[] = {
>> DREAM_GPIO_BANK("MISC2", 0x00, DREAM_GPIO_MISC2_BASE),
>> DREAM_GPIO_BANK("MISC3", 0x02, DREAM_GPIO_MISC3_BASE),
>> DREAM_GPIO_BANK("MISC4", 0x04, DREAM_GPIO_MISC4_BASE),
>> DREAM_GPIO_BANK("MISC5", 0x06, DREAM_GPIO_MISC5_BASE),
>> DREAM_GPIO_BANK("INT2", 0x08, DREAM_GPIO_INT2_BASE),
>> DREAM_GPIO_BANK("MISC1", 0x0a, DREAM_GPIO_MISC1_BASE),
>> DREAM_GPIO_BANK("VIRTUAL", 0x12, DREAM_GPIO_VIRTUAL_BASE),
>> };
>
> Yep, that did the trick.
>
>> With this you can now just access the dream_gpio_chip data in all
>> the member function using the to_dream_gpio_chip() macro.
>>
>> I agree with Ryan and think you would be better off in the long
>> run to re-code this and use gpiolib. You might also want to break
>> out all the gpio interrupt stuff and submit it as a seperate patch.
>
> Will do. Here's how the patch looks now.
>
> diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig
> index 1c4119c..8bb8546 100644
> --- a/arch/arm/Kconfig
> +++ b/arch/arm/Kconfig
> @@ -565,6 +565,8 @@ config ARCH_MSM
> select CPU_V6
> select GENERIC_TIME
> select GENERIC_CLOCKEVENTS
> + select GENERIC_GPIO
> + select ARCH_REQUIRE_GPIOLIB

I think you need to move these to MACH_TROUT since this is 'dream'
specific.

> help
> Support for Qualcomm MSM7K based systems. This runs on the ARM11
> apps processor of the MSM7K and depends on a shared memory
> diff --git a/arch/arm/mach-msm/Makefile b/arch/arm/mach-msm/Makefile
> index 91e6f5c..4c2567e 100644
> --- a/arch/arm/mach-msm/Makefile
> +++ b/arch/arm/mach-msm/Makefile
> @@ -6,4 +6,4 @@ obj-y += clock.o clock-7x01a.o
>
> obj-$(CONFIG_MACH_HALIBUT) += board-halibut.o
>
> -obj-$(CONFIG_MACH_TROUT) += board-dream.o
> +obj-$(CONFIG_MACH_TROUT) += board-dream.o board-dream-gpio.o generic_gpio.o
> diff --git a/arch/arm/mach-msm/board-dream-gpio.c b/arch/arm/mach-msm/board-dream-gpio.c
> new file mode 100644
> index 0000000..d90b8f9
> --- /dev/null
> +++ b/arch/arm/mach-msm/board-dream-gpio.c
> @@ -0,0 +1,135 @@
> +/*
> + * linux/arch/arm/mach-msm/gpio.c
> + *
> + * Copyright (C) 2005 HP Labs
> + * Copyright (C) 2008 Google, Inc.
> + * Copyright (C) 2009 Pavel Machek <[email protected]>
> + *
> + * This program is free software; you can redistribute it and/or modify
> + * it under the terms of the GNU General Public License as published by
> + * the Free Software Foundation; either version 2 of the License, or
> + * (at your option) any later version.
> + */
> +
> +#include <linux/clk.h>
> +#include <linux/errno.h>
> +#include <linux/interrupt.h>
> +#include <linux/irq.h>
> +#include <linux/debugfs.h>
> +#include <linux/seq_file.h>
> +#include <linux/kernel.h>
> +#include <linux/list.h>
> +#include <linux/module.h>
> +#include <linux/io.h>
> +#include <linux/gpio.h>
> +
> +#include <mach/hardware.h>
> +#include <mach/gpio.h>
> +
> +#include <asm/gpio.h>
> +
> +#include "board-dream.h"
> +

Please remove all the unnecessary headers. I think you only need:

#include <linux/kernel.h>
#include <linux/module.h>
#include <linux/io.h>
#include <linux/gpio.h>

#include <mach/hardware.h>
#include <mach/gpio.h>

#include "board-dream.h"

> +struct msm_gpio_chip {
> + struct gpio_chip chip;
> + void __iomem *reg; /* Base of register bank */
> + u8 shadow;
> +};
> +
> +#define to_msm_gpio_chip(c) container_of(c, struct msm_gpio_chip, chip)
> +
> +static void msm_gpiolib_set(struct gpio_chip *chip, unsigned offset, int val);
> +static int msm_gpiolib_get(struct gpio_chip *chip, unsigned offset);
> +static int msm_gpiolib_direction_output(struct gpio_chip *chip,
> + unsigned offset, int val);
> +static int msm_gpiolib_direction_input(struct gpio_chip *chip,
> + unsigned offset);
> +

Please reorganize the code so that the function prototypes are not
needed.

> +#define DREAM_GPIO_BANK(name, reg_num, base_gpio, shadow_val) \
> + { \
> + .chip = { \
> + .label = name, \
> + .direction_input = msm_gpiolib_direction_input, \
> + .direction_output = msm_gpiolib_direction_output, \
> + .get = msm_gpiolib_get, \
> + .set = msm_gpiolib_set, \
> + .base = base_gpio, \
> + .ngpio = 8, \
> + }, \
> + .reg = reg_num + DREAM_CPLD_BASE, \
> + .shadow = shadow_val, \
> + }
> +
> +static struct msm_gpio_chip msm_gpio_banks[] = {
> +#if defined(CONFIG_MSM_DEBUG_UART1)
> + /* H2W pins <-> UART1 */
> + DREAM_GPIO_BANK("MISC2", 0x00, DREAM_GPIO_MISC2_BASE, 0x40),
> +#else
> + /* H2W pins <-> UART3, Bluetooth <-> UART1 */
> + DREAM_GPIO_BANK("MISC2", 0x00, DREAM_GPIO_MISC2_BASE, 0x80),
> +#endif
> + /* I2C pull */
> + DREAM_GPIO_BANK("MISC3", 0x02, DREAM_GPIO_MISC3_BASE, 0x04),
> + DREAM_GPIO_BANK("MISC4", 0x04, DREAM_GPIO_MISC4_BASE, 0),
> + /* mmdi 32k en */
> + DREAM_GPIO_BANK("MISC5", 0x06, DREAM_GPIO_MISC5_BASE, 0x04),
> + DREAM_GPIO_BANK("INT2", 0x08, DREAM_GPIO_INT2_BASE, 0),
> + DREAM_GPIO_BANK("MISC1", 0x0a, DREAM_GPIO_MISC1_BASE, 0),
> + DREAM_GPIO_BANK("VIRTUAL", 0x12, DREAM_GPIO_VIRTUAL_BASE, 0),
> +};
> +
> +static int msm_gpiolib_get(struct gpio_chip *chip, unsigned offset)
> +{
> + struct msm_gpio_chip *msm_gpio = to_msm_gpio_chip(chip);
> + unsigned mask = 1 << offset;
> +
> + return !! (readb(msm_gpio->reg) & mask);
> +}
> +
> +static void msm_gpiolib_set(struct gpio_chip *chip, unsigned offset, int val)
> +{
> + struct msm_gpio_chip *msm_gpio = to_msm_gpio_chip(chip);
> + unsigned mask = 1 << offset;
> +
> + if (val)
> + msm_gpio->shadow |= mask;
> + else
> + msm_gpio->shadow &= ~mask;
> +
> + writeb(msm_gpio->shadow, msm_gpio->reg);
> +}
> +
> +static int msm_gpiolib_direction_input(struct gpio_chip *chip,
> + unsigned offset)
> +{
> + msm_gpiolib_set(chip, offset, 0);
> + return 0;
> +}
> +
> +static int msm_gpiolib_direction_output(struct gpio_chip *chip,
> + unsigned offset, int val)
> +{
> + msm_gpiolib_set(chip, offset, val);
> + return 0;
> +}
> +
> +int gpio_to_irq(unsigned gpio)
> +{
> + BUG();
> +}

return -EINVAL;

> +
> +/*
> + * Called from the processor-specific init to enable GPIO pin support.
> + */
> +int __init dream_init_gpio(void)
> +{
> + int i;
> +
> + for (i = 0; i < ARRAY_SIZE(msm_gpio_banks); i++)
> + gpiochip_add(&msm_gpio_banks[i].chip);
> +
> + return 0;
> +}

Your original patch was initially writing the shadow values to the registers.
Do you still need to do that?

> +
> +postcore_initcall(dream_init_gpio);
> +
> diff --git a/arch/arm/mach-msm/board-dream.h b/arch/arm/mach-msm/board-dream.h
> index 4f345a5..aab1faf 100644
> --- a/arch/arm/mach-msm/board-dream.h
> +++ b/arch/arm/mach-msm/board-dream.h
> @@ -1,5 +1,153 @@
>
> -#define TROUT_CPLD_BASE 0xE8100000
> -#define TROUT_CPLD_START 0x98000000
> -#define TROUT_CPLD_SIZE SZ_4K
> +#define MSM_SMI_BASE 0x00000000
> +#define MSM_SMI_SIZE 0x00800000
>
> +#define MSM_EBI_BASE 0x10000000
> +#define MSM_EBI_SIZE 0x06e00000
> +
> +#define MSM_PMEM_GPU0_BASE 0x00000000
> +#define MSM_PMEM_GPU0_SIZE 0x00700000
> +
> +#define MSM_PMEM_MDP_BASE 0x02000000
> +#define MSM_PMEM_MDP_SIZE 0x00800000
> +
> +#define MSM_PMEM_ADSP_BASE 0x02800000
> +#define MSM_PMEM_ADSP_SIZE 0x00800000
> +
> +#define MSM_PMEM_CAMERA_BASE 0x03000000
> +#define MSM_PMEM_CAMERA_SIZE 0x00800000
> +
> +#define MSM_FB_BASE 0x03800000
> +#define MSM_FB_SIZE 0x00100000
> +
> +#define MSM_LINUX_BASE MSM_EBI_BASE
> +#define MSM_LINUX_SIZE 0x06500000
> +
> +#define MSM_PMEM_GPU1_SIZE 0x800000
> +#define MSM_PMEM_GPU1_BASE (MSM_RAM_CONSOLE_BASE - MSM_PMEM_GPU1_SIZE)
> +
> +#define MSM_RAM_CONSOLE_BASE (MSM_EBI_BASE + 0x6d00000)
> +#define MSM_RAM_CONSOLE_SIZE (128 * SZ_1K)
> +
> +#if (MSM_FB_BASE + MSM_FB_SIZE) >= (MSM_PMEM_GPU1_BASE)
> +#error invalid memory map
> +#endif
> +
> +#define DECLARE_MSM_IOMAP
> +#include <mach/msm_iomap.h>
> +
> +#define DREAM_4_BALL_UP_0 1
> +#define DREAM_4_BALL_LEFT_0 18
> +#define DREAM_4_BALL_DOWN_0 57
> +#define DREAM_4_BALL_RIGHT_0 91
> +
> +#define DREAM_5_BALL_UP_0 94
> +#define DREAM_5_BALL_LEFT_0 18
> +#define DREAM_5_BALL_DOWN_0 90
> +#define DREAM_5_BALL_RIGHT_0 19
> +
> +#define DREAM_POWER_KEY 20
> +
> +#define DREAM_4_TP_LS_EN 19
> +#define DREAM_5_TP_LS_EN 1
> +
> +#define DREAM_CPLD_BASE 0xE8100000
> +#define DREAM_CPLD_START 0x98000000
> +#define DREAM_CPLD_SIZE SZ_4K
> +
> +#define DREAM_GPIO_CABLE_IN1 (83)
> +#define DREAM_GPIO_CABLE_IN2 (49)
> +
> +#define DREAM_GPIO_START (128)
> +
> +#define DREAM_GPIO_INT_MASK0_REG (0x0c)
> +#define DREAM_GPIO_INT_STAT0_REG (0x0e)
> +#define DREAM_GPIO_INT_MASK1_REG (0x14)
> +#define DREAM_GPIO_INT_STAT1_REG (0x10)
> +
> +#define DREAM_GPIO_HAPTIC_PWM (28)
> +#define DREAM_GPIO_PS_HOLD (25)
> +
> +#define DREAM_GPIO_MISC2_BASE (DREAM_GPIO_START + 0x00)
> +#define DREAM_GPIO_MISC3_BASE (DREAM_GPIO_START + 0x08)
> +#define DREAM_GPIO_MISC4_BASE (DREAM_GPIO_START + 0x10)
> +#define DREAM_GPIO_MISC5_BASE (DREAM_GPIO_START + 0x18)
> +#define DREAM_GPIO_INT2_BASE (DREAM_GPIO_START + 0x20)
> +#define DREAM_GPIO_MISC1_BASE (DREAM_GPIO_START + 0x28)
> +#define DREAM_GPIO_VIRTUAL_BASE (DREAM_GPIO_START + 0x30)
> +#define DREAM_GPIO_INT5_BASE (DREAM_GPIO_START + 0x48)
> +
> +#define DREAM_GPIO_CHARGER_EN (DREAM_GPIO_MISC2_BASE + 0)
> +#define DREAM_GPIO_ISET (DREAM_GPIO_MISC2_BASE + 1)
> +#define DREAM_GPIO_H2W_DAT_DIR (DREAM_GPIO_MISC2_BASE + 2)
> +#define DREAM_GPIO_H2W_CLK_DIR (DREAM_GPIO_MISC2_BASE + 3)
> +#define DREAM_GPIO_H2W_DAT_GPO (DREAM_GPIO_MISC2_BASE + 4)
> +#define DREAM_GPIO_H2W_CLK_GPO (DREAM_GPIO_MISC2_BASE + 5)
> +#define DREAM_GPIO_H2W_SEL0 (DREAM_GPIO_MISC2_BASE + 6)
> +#define DREAM_GPIO_H2W_SEL1 (DREAM_GPIO_MISC2_BASE + 7)
> +
> +#define DREAM_GPIO_SPOTLIGHT_EN (DREAM_GPIO_MISC3_BASE + 0)
> +#define DREAM_GPIO_FLASH_EN (DREAM_GPIO_MISC3_BASE + 1)
> +#define DREAM_GPIO_I2C_PULL (DREAM_GPIO_MISC3_BASE + 2)
> +#define DREAM_GPIO_TP_I2C_PULL (DREAM_GPIO_MISC3_BASE + 3)
> +#define DREAM_GPIO_TP_EN (DREAM_GPIO_MISC3_BASE + 4)
> +#define DREAM_GPIO_JOG_EN (DREAM_GPIO_MISC3_BASE + 5)
> +#define DREAM_GPIO_UI_LED_EN (DREAM_GPIO_MISC3_BASE + 6)
> +#define DREAM_GPIO_QTKEY_LED_EN (DREAM_GPIO_MISC3_BASE + 7)
> +
> +#define DREAM_GPIO_VCM_PWDN (DREAM_GPIO_MISC4_BASE + 0)
> +#define DREAM_GPIO_USB_H2W_SW (DREAM_GPIO_MISC4_BASE + 1)
> +#define DREAM_GPIO_COMPASS_RST_N (DREAM_GPIO_MISC4_BASE + 2)
> +#define DREAM_GPIO_HAPTIC_EN_UP (DREAM_GPIO_MISC4_BASE + 3)
> +#define DREAM_GPIO_HAPTIC_EN_MAIN (DREAM_GPIO_MISC4_BASE + 4)
> +#define DREAM_GPIO_USB_PHY_RST_N (DREAM_GPIO_MISC4_BASE + 5)
> +#define DREAM_GPIO_WIFI_PA_RESETX (DREAM_GPIO_MISC4_BASE + 6)
> +#define DREAM_GPIO_WIFI_EN (DREAM_GPIO_MISC4_BASE + 7)
> +
> +#define DREAM_GPIO_BT_32K_EN (DREAM_GPIO_MISC5_BASE + 0)
> +#define DREAM_GPIO_MAC_32K_EN (DREAM_GPIO_MISC5_BASE + 1)
> +#define DREAM_GPIO_MDDI_32K_EN (DREAM_GPIO_MISC5_BASE + 2)
> +#define DREAM_GPIO_COMPASS_32K_EN (DREAM_GPIO_MISC5_BASE + 3)
> +
> +#define DREAM_GPIO_NAVI_ACT_N (DREAM_GPIO_INT2_BASE + 0)
> +#define DREAM_GPIO_COMPASS_IRQ (DREAM_GPIO_INT2_BASE + 1)
> +#define DREAM_GPIO_SLIDING_DET (DREAM_GPIO_INT2_BASE + 2)
> +#define DREAM_GPIO_AUD_HSMIC_DET_N (DREAM_GPIO_INT2_BASE + 3)
> +#define DREAM_GPIO_SD_DOOR_N (DREAM_GPIO_INT2_BASE + 4)
> +#define DREAM_GPIO_CAM_BTN_STEP1_N (DREAM_GPIO_INT2_BASE + 5)
> +#define DREAM_GPIO_CAM_BTN_STEP2_N (DREAM_GPIO_INT2_BASE + 6)
> +#define DREAM_GPIO_TP_ATT_N (DREAM_GPIO_INT2_BASE + 7)
> +#define DREAM_GPIO_BANK0_FIRST_INT_SOURCE (DREAM_GPIO_NAVI_ACT_N)
> +#define DREAM_GPIO_BANK0_LAST_INT_SOURCE (DREAM_GPIO_TP_ATT_N)
> +
> +#define DREAM_GPIO_H2W_DAT_GPI (DREAM_GPIO_MISC1_BASE + 0)
> +#define DREAM_GPIO_H2W_CLK_GPI (DREAM_GPIO_MISC1_BASE + 1)
> +#define DREAM_GPIO_CPLD128_VER_0 (DREAM_GPIO_MISC1_BASE + 4)
> +#define DREAM_GPIO_CPLD128_VER_1 (DREAM_GPIO_MISC1_BASE + 5)
> +#define DREAM_GPIO_CPLD128_VER_2 (DREAM_GPIO_MISC1_BASE + 6)
> +#define DREAM_GPIO_CPLD128_VER_3 (DREAM_GPIO_MISC1_BASE + 7)
> +
> +#define DREAM_GPIO_SDMC_CD_N (DREAM_GPIO_VIRTUAL_BASE + 0)
> +#define DREAM_GPIO_END (DREAM_GPIO_SDMC_CD_N)
> +#define DREAM_GPIO_BANK1_FIRST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
> +#define DREAM_GPIO_BANK1_LAST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
> +
> +#define DREAM_GPIO_VIRTUAL_TO_REAL_OFFSET \
> + (DREAM_GPIO_INT5_BASE - DREAM_GPIO_VIRTUAL_BASE)
> +
> +#define DREAM_INT_START (NR_MSM_IRQS + NR_GPIO_IRQS)
> +#define DREAM_INT_BANK0_COUNT (8)
> +#define DREAM_INT_BANK1_START (DREAM_INT_START + DREAM_INT_BANK0_COUNT)
> +#define DREAM_INT_BANK1_COUNT (1)
> +#define DREAM_INT_END (DREAM_INT_START + DREAM_INT_BANK0_COUNT + \
> + DREAM_INT_BANK1_COUNT - 1)
> +#define DREAM_GPIO_TO_INT(n) (((n) <= DREAM_GPIO_BANK0_LAST_INT_SOURCE) ? \
> + (DREAM_INT_START - DREAM_GPIO_BANK0_FIRST_INT_SOURCE + (n)) : \
> + (DREAM_INT_BANK1_START - DREAM_GPIO_BANK1_FIRST_INT_SOURCE + (n)))
> +
> +#define DREAM_INT_TO_BANK(n) ((n - DREAM_INT_START) / DREAM_INT_BANK0_COUNT)
> +#define DREAM_INT_TO_MASK(n) (1U << ((n - DREAM_INT_START) & 7))
> +#define DREAM_BANK_TO_MASK_REG(bank) \
> + (bank ? DREAM_GPIO_INT_MASK1_REG : DREAM_GPIO_INT_MASK0_REG)
> +#define DREAM_BANK_TO_STAT_REG(bank) \
> + (bank ? DREAM_GPIO_INT_STAT1_REG : DREAM_GPIO_INT_STAT0_REG)

I think all the DREAM_GPIO_* stuff needs to be moved into
arch/arm/mach-msm/include/mach/gpio.h so that board drivers can pick up
the defines with #include <linux/gpio.h>.

> diff --git a/arch/arm/mach-msm/include/mach/gpio.h b/arch/arm/mach-msm/include/mach/gpio.h
> new file mode 100644
> index 0000000..92ce18d
> --- /dev/null
> +++ b/arch/arm/mach-msm/include/mach/gpio.h
> @@ -0,0 +1,36 @@
> +/* linux/include/asm-arm/arch-msm/gpio.h
> + *
> + * Copyright (C) 2007 Google, Inc.
> + * Author: Mike Lockwood <[email protected]>
> + *
> + * This software is licensed under the terms of the GNU General Public
> + * License version 2, as published by the Free Software Foundation, and
> + * may be copied, distributed, and modified under those terms.
> + *
> + * This program is distributed in the hope that 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.
> + *
> + */
> +
> +#ifndef __ASM_ARCH_MSM_GPIO_H
> +#define __ASM_ARCH_MSM_GPIO_H
> +
> +#include <linux/interrupt.h>

Unneeded include.

> +
> +int gpio_request(unsigned gpio, const char *label);
> +void gpio_free(unsigned gpio);
> +int gpio_direction_input(unsigned gpio);
> +int gpio_direction_output(unsigned gpio, int value);
> +int gpio_get_value(unsigned gpio);
> +void gpio_set_value(unsigned gpio, int value);
> +int gpio_to_irq(unsigned gpio);
> +

The prototypes are not needed. They will get picked up by the
following include.

> +#include <asm-generic/gpio.h>
> +
> +extern int gpio_configure(unsigned int gpio, unsigned long flags);
> +extern int gpio_read_detect_status(unsigned int gpio);
> +extern int gpio_clear_detect_status(unsigned int gpio);

These are not needed since they are not defined in the patch.

I think you will need to add the following also so that gpiolib will
use the default functions.

#define gpio_get_value __gpio_get_value
#define gpio_set_value __gpio_set_value
#define gpio_cansleep __gpio_cansleep

> +
> +#endif

Regards,
Hartley

2009-12-11 23:12:31

by Hartley Sweeten

[permalink] [raw]
Subject: RE: GPIO support for HTC Dream

On Friday, December 11, 2009 3:41 PM, Arve Hj?nnev?g wrote:

<snip>

>> Now, it will still need some cleanups -- I'm not sure if gpios are
>> dream-specific or generic for whole msm.... I kind of assume they
>> should be generic for msm. Google people, can you help?
>
> I'm not exactly sure what you are asking. Gpios in general are not
> dream specific, the code in board-dream-gpio.c is. Some gpios (e.g.
> DREAM_4_BALL_UP_0) are used for a dream specific function, but point
> to a gpio that is generic to the msm architecture.

<snip>

>> diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig
>> index 1c4119c..8bb8546 100644
>> --- a/arch/arm/Kconfig
>> +++ b/arch/arm/Kconfig
>> @@ -565,6 +565,8 @@ config ARCH_MSM
>> ? ? ? ?select CPU_V6
>> ? ? ? ?select GENERIC_TIME
>> ? ? ? ?select GENERIC_CLOCKEVENTS
>> + ? ? ? select GENERIC_GPIO
>> + ? ? ? select ARCH_REQUIRE_GPIOLIB
>
> Please do not do this in a board specific change. You have not changed
> the msm generic gpio support to use gpiolib.

Where is the msm tree located? mach-msm in mainline doesn't appear to
have _any_ gpio support. Is Pavel's implementation generic enough to
work with any msm based board?

Regards,
Hartley

2009-12-11 23:35:20

by Russell King - ARM Linux

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Fri, Dec 11, 2009 at 11:10:15PM +0100, Pavel Machek wrote:
> +#include <linux/gpio.h>
...
> +#include <mach/gpio.h>
...
> +#include <asm/gpio.h>

Emm, this is getting really silly.

include/linux/gpio.h:

#ifdef CONFIG_GENERIC_GPIO
#include <asm/gpio.h>
#else
...
#endif

arch/arm/include/asm/gpio.h:

#include <mach/gpio.h>

There really is no point in including mach/gpio.h nor asm/gpio.h when
linux/gpio.h will do. I'm retiscent to add #warnings or #errors into
these files, but it seems that this is such a common thing that it may
be beneficial to do so.

2009-12-11 23:50:27

by Hartley Sweeten

[permalink] [raw]
Subject: RE: GPIO support for HTC Dream

On Friday, December 11, 2009 4:29 PM, Russell King wrote:
> On Fri, Dec 11, 2009 at 11:10:15PM +0100, Pavel Machek wrote:
>> +#include <linux/gpio.h>
> ...
>> +#include <mach/gpio.h>
> ...
>> +#include <asm/gpio.h>
>
> Emm, this is getting really silly.
>
> include/linux/gpio.h:
>
> #ifdef CONFIG_GENERIC_GPIO
> #include <asm/gpio.h>
> #else
> ...
> #endif
>
> arch/arm/include/asm/gpio.h:
>
> #include <mach/gpio.h>
>
> There really is no point in including mach/gpio.h nor asm/gpio.h when
> linux/gpio.h will do. I'm retiscent to add #warnings or #errors into
> these files, but it seems that this is such a common thing that it may
> be beneficial to do so.

Hi Russell,

I think you mentioned last year around this time, when the big header
move occurred, that you were going to add a guideline for mach/*.h
headers to Documentation/arm. Maybe it's time to add that patch and
just note that the <linux/*.h> version of the common headers should
be used and that the <asm/*.h> and <mach/*.h> header gets pulled in
automatically.

I think the two big ones that everyone screws up are, <linux/gpio.h>
and <linux/io.h>.

Regards,
Hartley

2009-12-13 21:29:26

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Wed 2009-12-09 08:18:15, Daniel Walker wrote:
> On Wed, 2009-12-09 at 12:37 +0100, Pavel Machek wrote:
> > On Tue 2009-12-08 16:39:09, Arve Hj?nnev?g wrote:
> > > On Tue, Dec 8, 2009 at 2:45 PM, Russell King - ARM Linux
> > > <[email protected]> wrote:
> > > > On Tue, Dec 08, 2009 at 11:28:43AM +0100, Pavel Machek wrote:
> > > >> Add GPIO support for HTC Dream.
> > > >>
> > > >> Signed-off-by: Pavel Machek <[email protected]>
> > > >>
> > > >> diff --git a/arch/arm/mach-msm/Kconfig b/arch/arm/mach-msm/Kconfig
> > > >> index f780086..774c50e 100644
> > > >> --- a/arch/arm/mach-msm/Kconfig
> > > >> +++ b/arch/arm/mach-msm/Kconfig
> > > >> @@ -40,4 +40,8 @@ config MACH_TROUT
> > > >> help
> > > >> Support for the HTC Dream, T-Mobile G1, Android ADP1 devices.
> > > >>
> > > >> +config GENERIC_GPIO
> > > >> + bool
> > > >> + default y
> > > >
> > > > Please arrange for this to be handled just like every other ARM
> > > > platform via a 'select' statement - eg:
> > > >
> > > > config ARCH_AT91
> > > > bool "Atmel AT91"
> > > > select GENERIC_GPIO
> > > > select ARCH_REQUIRE_GPIOLIB
> > > > select HAVE_CLK
> > > >
> > > > It is not nice to have multiple definitions of the same symbol scattered
> > > > throughout the Kconfig files.
> > > >
> > >
> > > Why did this code get pulled into the dream gpio code? The original
> > > change that adds msm gpio support already selects GENERIC_GPIO
> > > (http://android.git.kernel.org/?p=kernel/msm.git;a=commit;h=5ae9f4403530a5782478c35d29753081750c4188).
> > > Since you copied half of the files from that change anyway, it would
> > > be better to just include that change in you patch set.
> >
> > I'm not sure how to do that with git without pulling all the changes
> > before that one, too :-(.
>
> I'm going to end up pulling a lot of these git commit into my git tree.
> It would be pretty easy for me to just pull this GPIO change directly ..
> I assume you haven't found a way to work with git that suites you? It
> would be best if you used git, but I could try to do some sort of quilt
> export if that works better for you.

I can easily "pull" git trees. I do my own work in git, but usually
not in a way that would be useful for pushing upstream (see my trees
at git.kernel.org).

I *could* add my dream trees to those that are mirrored at kernel.org,
when things settle a bit. (Should I?)

But I'd really prefer to push my stuff using plain old patches in
emails.
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-13 21:52:10

by Brian Swetland

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Sun, Dec 13, 2009 at 1:29 PM, Pavel Machek <[email protected]> wrote:
>>
>> I'm going to end up pulling a lot of these git commit into my git tree.
>> It would be pretty easy for me to just pull this GPIO change directly ..
>> I assume you haven't found a way to work with git that suites you? It
>> would be best if you used git, but I could try to do some sort of quilt
>> export if that works better for you.
>
> I can easily "pull" git trees. I do my own work in git, but usually
> not in a way that would be useful for pushing upstream (see my trees
> at git.kernel.org).
>
> I *could* add my dream trees to those that are mirrored at kernel.org,
> when things settle a bit. (Should I?)
>
> But I'd really prefer to push my stuff using plain old patches in
> emails.

It would probably be helpful for those of us at Google and Qualcomm,
who have an entirely git-based workflow to be able to pull patches
from somewhere, especially if you already have trees that you could
publish and it's not a huge burden on you.

What has worked well for me the last couple times I've sent patches
out was to put them in an outgoing git branch somewhere, use the git
tools to email them to lkml/lakml for review, and include a pointer to
the git://... that people can pull from -- sorta the best of both
worlds.

Brian

2009-12-14 06:24:47

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Fri 2009-12-11 23:28:38, Russell King - ARM Linux wrote:
> On Fri, Dec 11, 2009 at 11:10:15PM +0100, Pavel Machek wrote:
> > +#include <linux/gpio.h>
> ...
> > +#include <mach/gpio.h>
> ...
> > +#include <asm/gpio.h>
>
> Emm, this is getting really silly.
>
> include/linux/gpio.h:
>
> #ifdef CONFIG_GENERIC_GPIO
> #include <asm/gpio.h>
> #else
> ...
> #endif
>
> arch/arm/include/asm/gpio.h:
>
> #include <mach/gpio.h>

Fixed, thanks.

--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-14 06:46:00

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

Hi!

> This looks MUCH better!

Thanks :-).

> > arch/arm/Kconfig | 1
> > arch/arm/mach-msm/board-dream-gpio.c | 327 +++++++++--------------------------
...
> Please update (or remove) this diffstat. It no longer matches the patch.

I was just showing differences to _previous_ version, not what I was sending.

> Ok. The hardware still seems a bit strange. Is there any datasheet
> available?

I don't think there is one. Daniel, can you help here?

> Please remove all the unnecessary headers. I think you only need:
>
> #include <linux/kernel.h>
...
> #include "board-dream.h"

Yep, right, thanks.

> > +static void msm_gpiolib_set(struct gpio_chip *chip, unsigned offset, int val);
...
> > +static int msm_gpiolib_direction_input(struct gpio_chip *chip,
> > + unsigned offset);
>
> Please reorganize the code so that the function prototypes are not
> needed.

Done.

> > +int gpio_to_irq(unsigned gpio)
> > +{
> > + BUG();
> > +}
>
> return -EINVAL;

Ok.

> > +int __init dream_init_gpio(void)
> > +{
> > + int i;
> > +
> > + for (i = 0; i < ARRAY_SIZE(msm_gpio_banks); i++)
> > + gpiochip_add(&msm_gpio_banks[i].chip);
> > +
> > + return 0;
> > +}
>
> Your original patch was initially writing the shadow values to the registers.
> Do you still need to do that?

It seems to boot this way :-). If writing the shadow values is not
needed, lets try getting away without it...

> > +#define DREAM_INT_TO_BANK(n) ((n - DREAM_INT_START) / DREAM_INT_BANK0_COUNT)
> > +#define DREAM_INT_TO_MASK(n) (1U << ((n - DREAM_INT_START) & 7))
> > +#define DREAM_BANK_TO_MASK_REG(bank) \
> > + (bank ? DREAM_GPIO_INT_MASK1_REG : DREAM_GPIO_INT_MASK0_REG)
> > +#define DREAM_BANK_TO_STAT_REG(bank) \
> > + (bank ? DREAM_GPIO_INT_STAT1_REG : DREAM_GPIO_INT_STAT0_REG)
>
> I think all the DREAM_GPIO_* stuff needs to be moved into
> arch/arm/mach-msm/include/mach/gpio.h so that board drivers can pick up
> the defines with #include <linux/gpio.h>.

Ok, done. Plus I removed IRQ defines -- they are not needed now and
patch using them should probably add them.

> > +#include <linux/interrupt.h>
>
> Unneeded include.

Deleted.

> > +int gpio_request(unsigned gpio, const char *label);
...
> > +int gpio_to_irq(unsigned gpio);
>
> The prototypes are not needed. They will get picked up by the
> following include.

gpio_to_irq seems needed, I killed the others.

> > +#include <asm-generic/gpio.h>
> > +
> > +extern int gpio_configure(unsigned int gpio, unsigned long flags);
> > +extern int gpio_read_detect_status(unsigned int gpio);
> > +extern int gpio_clear_detect_status(unsigned int gpio);
>
> These are not needed since they are not defined in the patch.
>
> I think you will need to add the following also so that gpiolib will
> use the default functions.
>
> #define gpio_get_value __gpio_get_value
> #define gpio_set_value __gpio_set_value
> #define gpio_cansleep __gpio_cansleep

Yep, thanks!

It now looks like this. I still need to test it and clean up
warnings. (and move those selects)
Pavel

diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig
index 1c4119c..8bb8546 100644
--- a/arch/arm/Kconfig
+++ b/arch/arm/Kconfig
@@ -565,6 +565,8 @@ config ARCH_MSM
select CPU_V6
select GENERIC_TIME
select GENERIC_CLOCKEVENTS
+ select GENERIC_GPIO
+ select ARCH_REQUIRE_GPIOLIB
help
Support for Qualcomm MSM7K based systems. This runs on the ARM11
apps processor of the MSM7K and depends on a shared memory
diff --git a/arch/arm/mach-msm/Makefile b/arch/arm/mach-msm/Makefile
index 91e6f5c..4c2567e 100644
--- a/arch/arm/mach-msm/Makefile
+++ b/arch/arm/mach-msm/Makefile
@@ -6,4 +6,4 @@ obj-y += clock.o clock-7x01a.o

obj-$(CONFIG_MACH_HALIBUT) += board-halibut.o

-obj-$(CONFIG_MACH_TROUT) += board-dream.o
+obj-$(CONFIG_MACH_TROUT) += board-dream.o board-dream-gpio.o generic_gpio.o
diff --git a/arch/arm/mach-msm/board-dream-gpio.c b/arch/arm/mach-msm/board-dream-gpio.c
new file mode 100644
index 0000000..4cf6ec0
--- /dev/null
+++ b/arch/arm/mach-msm/board-dream-gpio.c
@@ -0,0 +1,116 @@
+/*
+ * linux/arch/arm/mach-msm/gpio.c
+ *
+ * Copyright (C) 2005 HP Labs
+ * Copyright (C) 2008 Google, Inc.
+ * Copyright (C) 2009 Pavel Machek <[email protected]>
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ */
+
+#include <linux/kernel.h>
+#include <linux/module.h>
+#include <linux/io.h>
+#include <linux/gpio.h>
+
+#include "board-dream.h"
+
+struct msm_gpio_chip {
+ struct gpio_chip chip;
+ void __iomem *reg; /* Base of register bank */
+ u8 shadow;
+};
+
+#define to_msm_gpio_chip(c) container_of(c, struct msm_gpio_chip, chip)
+
+static int msm_gpiolib_get(struct gpio_chip *chip, unsigned offset)
+{
+ struct msm_gpio_chip *msm_gpio = to_msm_gpio_chip(chip);
+ unsigned mask = 1 << offset;
+
+ return !! (readb(msm_gpio->reg) & mask);
+}
+
+static void msm_gpiolib_set(struct gpio_chip *chip, unsigned offset, int val)
+{
+ struct msm_gpio_chip *msm_gpio = to_msm_gpio_chip(chip);
+ unsigned mask = 1 << offset;
+
+ if (val)
+ msm_gpio->shadow |= mask;
+ else
+ msm_gpio->shadow &= ~mask;
+
+ writeb(msm_gpio->shadow, msm_gpio->reg);
+}
+
+static int msm_gpiolib_direction_input(struct gpio_chip *chip,
+ unsigned offset)
+{
+ msm_gpiolib_set(chip, offset, 0);
+ return 0;
+}
+
+static int msm_gpiolib_direction_output(struct gpio_chip *chip,
+ unsigned offset, int val)
+{
+ msm_gpiolib_set(chip, offset, val);
+ return 0;
+}
+
+int gpio_to_irq(unsigned gpio)
+{
+ return -EINVAL;
+}
+
+#define DREAM_GPIO_BANK(name, reg_num, base_gpio, shadow_val) \
+ { \
+ .chip = { \
+ .label = name, \
+ .direction_input = msm_gpiolib_direction_input, \
+ .direction_output = msm_gpiolib_direction_output, \
+ .get = msm_gpiolib_get, \
+ .set = msm_gpiolib_set, \
+ .base = base_gpio, \
+ .ngpio = 8, \
+ }, \
+ .reg = reg_num + DREAM_CPLD_BASE, \
+ .shadow = shadow_val, \
+ }
+
+static struct msm_gpio_chip msm_gpio_banks[] = {
+#if defined(CONFIG_MSM_DEBUG_UART1)
+ /* H2W pins <-> UART1 */
+ DREAM_GPIO_BANK("MISC2", 0x00, DREAM_GPIO_MISC2_BASE, 0x40),
+#else
+ /* H2W pins <-> UART3, Bluetooth <-> UART1 */
+ DREAM_GPIO_BANK("MISC2", 0x00, DREAM_GPIO_MISC2_BASE, 0x80),
+#endif
+ /* I2C pull */
+ DREAM_GPIO_BANK("MISC3", 0x02, DREAM_GPIO_MISC3_BASE, 0x04),
+ DREAM_GPIO_BANK("MISC4", 0x04, DREAM_GPIO_MISC4_BASE, 0),
+ /* mmdi 32k en */
+ DREAM_GPIO_BANK("MISC5", 0x06, DREAM_GPIO_MISC5_BASE, 0x04),
+ DREAM_GPIO_BANK("INT2", 0x08, DREAM_GPIO_INT2_BASE, 0),
+ DREAM_GPIO_BANK("MISC1", 0x0a, DREAM_GPIO_MISC1_BASE, 0),
+ DREAM_GPIO_BANK("VIRTUAL", 0x12, DREAM_GPIO_VIRTUAL_BASE, 0),
+};
+
+/*
+ * Called from the processor-specific init to enable GPIO pin support.
+ */
+int __init dream_init_gpio(void)
+{
+ int i;
+
+ for (i = 0; i < ARRAY_SIZE(msm_gpio_banks); i++)
+ gpiochip_add(&msm_gpio_banks[i].chip);
+
+ return 0;
+}
+
+postcore_initcall(dream_init_gpio);
+
diff --git a/arch/arm/mach-msm/board-dream.h b/arch/arm/mach-msm/board-dream.h
index 4f345a5..dbd78b9 100644
--- a/arch/arm/mach-msm/board-dream.h
+++ b/arch/arm/mach-msm/board-dream.h
@@ -1,5 +1,58 @@

-#define TROUT_CPLD_BASE 0xE8100000
-#define TROUT_CPLD_START 0x98000000
-#define TROUT_CPLD_SIZE SZ_4K
+#define MSM_SMI_BASE 0x00000000
+#define MSM_SMI_SIZE 0x00800000
+
+#define MSM_EBI_BASE 0x10000000
+#define MSM_EBI_SIZE 0x06e00000
+
+#define MSM_PMEM_GPU0_BASE 0x00000000
+#define MSM_PMEM_GPU0_SIZE 0x00700000
+
+#define MSM_PMEM_MDP_BASE 0x02000000
+#define MSM_PMEM_MDP_SIZE 0x00800000
+
+#define MSM_PMEM_ADSP_BASE 0x02800000
+#define MSM_PMEM_ADSP_SIZE 0x00800000
+
+#define MSM_PMEM_CAMERA_BASE 0x03000000
+#define MSM_PMEM_CAMERA_SIZE 0x00800000
+
+#define MSM_FB_BASE 0x03800000
+#define MSM_FB_SIZE 0x00100000
+
+#define MSM_LINUX_BASE MSM_EBI_BASE
+#define MSM_LINUX_SIZE 0x06500000
+
+#define MSM_PMEM_GPU1_SIZE 0x800000
+#define MSM_PMEM_GPU1_BASE (MSM_RAM_CONSOLE_BASE - MSM_PMEM_GPU1_SIZE)
+
+#define MSM_RAM_CONSOLE_BASE (MSM_EBI_BASE + 0x6d00000)
+#define MSM_RAM_CONSOLE_SIZE (128 * SZ_1K)
+
+#if (MSM_FB_BASE + MSM_FB_SIZE) >= (MSM_PMEM_GPU1_BASE)
+#error invalid memory map
+#endif
+
+#define DECLARE_MSM_IOMAP
+#include <mach/msm_iomap.h>
+
+#define DREAM_4_BALL_UP_0 1
+#define DREAM_4_BALL_LEFT_0 18
+#define DREAM_4_BALL_DOWN_0 57
+#define DREAM_4_BALL_RIGHT_0 91
+
+#define DREAM_5_BALL_UP_0 94
+#define DREAM_5_BALL_LEFT_0 18
+#define DREAM_5_BALL_DOWN_0 90
+#define DREAM_5_BALL_RIGHT_0 19
+
+#define DREAM_POWER_KEY 20
+
+#define DREAM_4_TP_LS_EN 19
+#define DREAM_5_TP_LS_EN 1
+
+#define DREAM_CPLD_BASE 0xE8100000
+#define DREAM_CPLD_START 0x98000000
+#define DREAM_CPLD_SIZE SZ_4K
+

diff --git a/arch/arm/mach-msm/generic_gpio.c b/arch/arm/mach-msm/generic_gpio.c
new file mode 100644
index 0000000..357e63e
--- /dev/null
+++ b/arch/arm/mach-msm/generic_gpio.c
@@ -0,0 +1,15 @@
+/* arch/arm/mach-msm/generic_gpio.c
+ *
+ * Copyright (C) 2007 Google, Inc.
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that 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.
+ *
+ */
+
diff --git a/arch/arm/mach-msm/gpio_chip.h b/arch/arm/mach-msm/gpio_chip.h
new file mode 100644
index 0000000..ffc4d54
--- /dev/null
+++ b/arch/arm/mach-msm/gpio_chip.h
@@ -0,0 +1,20 @@
+/* arch/arm/mach-msm/gpio_chip.h
+ *
+ * Copyright (C) 2007 Google, Inc.
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that 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.
+ *
+ */
+
+#ifndef _LINUX_GPIO_CHIP_H
+#define _LINUX_GPIO_CHIP_H
+
+
+#endif
diff --git a/arch/arm/mach-msm/include/mach/gpio.h b/arch/arm/mach-msm/include/mach/gpio.h
new file mode 100644
index 0000000..e92bc31
--- /dev/null
+++ b/arch/arm/mach-msm/include/mach/gpio.h
@@ -0,0 +1,105 @@
+/*
+ * Copyright (C) 2007 Google, Inc.
+ * Author: Mike Lockwood <[email protected]>
+ * Copyright (C) 2009 Pavel Machek <[email protected]>
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that 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.
+ *
+ */
+
+#ifndef __ASM_ARCH_MSM_GPIO_H
+#define __ASM_ARCH_MSM_GPIO_H
+
+extern int gpio_to_irq(unsigned gpio);
+
+#include <asm-generic/gpio.h>
+
+#define gpio_get_value __gpio_get_value
+#define gpio_set_value __gpio_set_value
+#define gpio_cansleep __gpio_cansleep
+
+#define DREAM_GPIO_CABLE_IN1 (83)
+#define DREAM_GPIO_CABLE_IN2 (49)
+
+#define DREAM_GPIO_START (128)
+
+#define DREAM_GPIO_INT_MASK0_REG (0x0c)
+#define DREAM_GPIO_INT_STAT0_REG (0x0e)
+#define DREAM_GPIO_INT_MASK1_REG (0x14)
+#define DREAM_GPIO_INT_STAT1_REG (0x10)
+
+#define DREAM_GPIO_HAPTIC_PWM (28)
+#define DREAM_GPIO_PS_HOLD (25)
+
+#define DREAM_GPIO_MISC2_BASE (DREAM_GPIO_START + 0x00)
+#define DREAM_GPIO_MISC3_BASE (DREAM_GPIO_START + 0x08)
+#define DREAM_GPIO_MISC4_BASE (DREAM_GPIO_START + 0x10)
+#define DREAM_GPIO_MISC5_BASE (DREAM_GPIO_START + 0x18)
+#define DREAM_GPIO_INT2_BASE (DREAM_GPIO_START + 0x20)
+#define DREAM_GPIO_MISC1_BASE (DREAM_GPIO_START + 0x28)
+#define DREAM_GPIO_VIRTUAL_BASE (DREAM_GPIO_START + 0x30)
+#define DREAM_GPIO_INT5_BASE (DREAM_GPIO_START + 0x48)
+
+#define DREAM_GPIO_CHARGER_EN (DREAM_GPIO_MISC2_BASE + 0)
+#define DREAM_GPIO_ISET (DREAM_GPIO_MISC2_BASE + 1)
+#define DREAM_GPIO_H2W_DAT_DIR (DREAM_GPIO_MISC2_BASE + 2)
+#define DREAM_GPIO_H2W_CLK_DIR (DREAM_GPIO_MISC2_BASE + 3)
+#define DREAM_GPIO_H2W_DAT_GPO (DREAM_GPIO_MISC2_BASE + 4)
+#define DREAM_GPIO_H2W_CLK_GPO (DREAM_GPIO_MISC2_BASE + 5)
+#define DREAM_GPIO_H2W_SEL0 (DREAM_GPIO_MISC2_BASE + 6)
+#define DREAM_GPIO_H2W_SEL1 (DREAM_GPIO_MISC2_BASE + 7)
+
+#define DREAM_GPIO_SPOTLIGHT_EN (DREAM_GPIO_MISC3_BASE + 0)
+#define DREAM_GPIO_FLASH_EN (DREAM_GPIO_MISC3_BASE + 1)
+#define DREAM_GPIO_I2C_PULL (DREAM_GPIO_MISC3_BASE + 2)
+#define DREAM_GPIO_TP_I2C_PULL (DREAM_GPIO_MISC3_BASE + 3)
+#define DREAM_GPIO_TP_EN (DREAM_GPIO_MISC3_BASE + 4)
+#define DREAM_GPIO_JOG_EN (DREAM_GPIO_MISC3_BASE + 5)
+#define DREAM_GPIO_UI_LED_EN (DREAM_GPIO_MISC3_BASE + 6)
+#define DREAM_GPIO_QTKEY_LED_EN (DREAM_GPIO_MISC3_BASE + 7)
+
+#define DREAM_GPIO_VCM_PWDN (DREAM_GPIO_MISC4_BASE + 0)
+#define DREAM_GPIO_USB_H2W_SW (DREAM_GPIO_MISC4_BASE + 1)
+#define DREAM_GPIO_COMPASS_RST_N (DREAM_GPIO_MISC4_BASE + 2)
+#define DREAM_GPIO_HAPTIC_EN_UP (DREAM_GPIO_MISC4_BASE + 3)
+#define DREAM_GPIO_HAPTIC_EN_MAIN (DREAM_GPIO_MISC4_BASE + 4)
+#define DREAM_GPIO_USB_PHY_RST_N (DREAM_GPIO_MISC4_BASE + 5)
+#define DREAM_GPIO_WIFI_PA_RESETX (DREAM_GPIO_MISC4_BASE + 6)
+#define DREAM_GPIO_WIFI_EN (DREAM_GPIO_MISC4_BASE + 7)
+
+#define DREAM_GPIO_BT_32K_EN (DREAM_GPIO_MISC5_BASE + 0)
+#define DREAM_GPIO_MAC_32K_EN (DREAM_GPIO_MISC5_BASE + 1)
+#define DREAM_GPIO_MDDI_32K_EN (DREAM_GPIO_MISC5_BASE + 2)
+#define DREAM_GPIO_COMPASS_32K_EN (DREAM_GPIO_MISC5_BASE + 3)
+
+#define DREAM_GPIO_NAVI_ACT_N (DREAM_GPIO_INT2_BASE + 0)
+#define DREAM_GPIO_COMPASS_IRQ (DREAM_GPIO_INT2_BASE + 1)
+#define DREAM_GPIO_SLIDING_DET (DREAM_GPIO_INT2_BASE + 2)
+#define DREAM_GPIO_AUD_HSMIC_DET_N (DREAM_GPIO_INT2_BASE + 3)
+#define DREAM_GPIO_SD_DOOR_N (DREAM_GPIO_INT2_BASE + 4)
+#define DREAM_GPIO_CAM_BTN_STEP1_N (DREAM_GPIO_INT2_BASE + 5)
+#define DREAM_GPIO_CAM_BTN_STEP2_N (DREAM_GPIO_INT2_BASE + 6)
+#define DREAM_GPIO_TP_ATT_N (DREAM_GPIO_INT2_BASE + 7)
+#define DREAM_GPIO_BANK0_FIRST_INT_SOURCE (DREAM_GPIO_NAVI_ACT_N)
+#define DREAM_GPIO_BANK0_LAST_INT_SOURCE (DREAM_GPIO_TP_ATT_N)
+
+#define DREAM_GPIO_H2W_DAT_GPI (DREAM_GPIO_MISC1_BASE + 0)
+#define DREAM_GPIO_H2W_CLK_GPI (DREAM_GPIO_MISC1_BASE + 1)
+#define DREAM_GPIO_CPLD128_VER_0 (DREAM_GPIO_MISC1_BASE + 4)
+#define DREAM_GPIO_CPLD128_VER_1 (DREAM_GPIO_MISC1_BASE + 5)
+#define DREAM_GPIO_CPLD128_VER_2 (DREAM_GPIO_MISC1_BASE + 6)
+#define DREAM_GPIO_CPLD128_VER_3 (DREAM_GPIO_MISC1_BASE + 7)
+
+#define DREAM_GPIO_SDMC_CD_N (DREAM_GPIO_VIRTUAL_BASE + 0)
+#define DREAM_GPIO_END (DREAM_GPIO_SDMC_CD_N)
+#define DREAM_GPIO_BANK1_FIRST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
+#define DREAM_GPIO_BANK1_LAST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
+
+#endif


--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-14 17:57:16

by Daniel Walker

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Sun, 2009-12-13 at 22:29 +0100, Pavel Machek wrote:

> > I'm going to end up pulling a lot of these git commit into my git tree.
> > It would be pretty easy for me to just pull this GPIO change directly ..
> > I assume you haven't found a way to work with git that suites you? It
> > would be best if you used git, but I could try to do some sort of quilt
> > export if that works better for you.
>
> I can easily "pull" git trees. I do my own work in git, but usually
> not in a way that would be useful for pushing upstream (see my trees
> at git.kernel.org).
>
> I *could* add my dream trees to those that are mirrored at kernel.org,
> when things settle a bit. (Should I?)

I'm not sure I know what you mean .. What benefit would that have?

> But I'd really prefer to push my stuff using plain old patches in
> emails.

What I was meaning is you need to keep track of my tree via git, just so
you know what's going into it and can work off it. If your already doing
that, then no problem ..

Daniel

2009-12-14 17:57:20

by Daniel Walker

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Mon, 2009-12-14 at 07:45 +0100, Pavel Machek wrote:
> Hi!
>
> > This looks MUCH better!
>
> Thanks :-).
>
> > > arch/arm/Kconfig | 1
> > > arch/arm/mach-msm/board-dream-gpio.c | 327 +++++++++--------------------------
> ...
> > Please update (or remove) this diffstat. It no longer matches the patch.
>
> I was just showing differences to _previous_ version, not what I was sending.
>
> > Ok. The hardware still seems a bit strange. Is there any datasheet
> > available?
>
> I don't think there is one. Daniel, can you help here?

I don't know if there is one or not (I'd guess not).. I can't release
documents, but I could try to address specific questions or find people
to answer specific questions.

Daniel

2009-12-14 18:12:34

by Hartley Sweeten

[permalink] [raw]
Subject: RE: GPIO support for HTC Dream

On Monday, December 14, 2009 10:55 AM, Daniel Walker wrote:
> On Mon, 2009-12-14 at 07:45 +0100, Pavel Machek wrote:
>> Hi!
>>
>>> This looks MUCH better!
>>
>> Thanks :-).
>>
>>>> arch/arm/Kconfig | 1
>>>> arch/arm/mach-msm/board-dream-gpio.c | 327 +++++++++--------------------------
>> ...
>>> Please update (or remove) this diffstat. It no longer matches the patch.
>>
>> I was just showing differences to _previous_ version, not what I was sending.
>>
>>> Ok. The hardware still seems a bit strange. Is there any datasheet
>>> available?
>>
>> I don't think there is one. Daniel, can you help here?
>
> I don't know if there is one or not (I'd guess not).. I can't release
> documents, but I could try to address specific questions or find people
> to answer specific questions.

Hello Daniel,

My specific question was about the gpio hardware registers.

>From Pavel's implementation it appears that the gpio's are organized as a
number of 8-bit ports. Each of these ports only have one 8-bit register.
Writing a '1' to a bit in the register makes the associated pin a high-level
output. Writing a '0' makes the pin a low-level output or an input pin.
Reading the port at this point will return the actual 'input' level of the pin.

The hardware seems a bit strange and I just wanted to verify that this is
correct. If it is, this would explain the need to keep the 'shadow' contents
of the port in order to set the 'direction' of a pin.

I was also wondering if the initial 'shadow' value needs to be written to the
port at init in order to correctly establish the output value for specific
pins.

One other thing. Are the gpio's handled by Pavel's driver actually from the
MSM chip or from an external CPLD? The registers are all defined as:

+ .reg = reg_num + DREAM_CPLD_BASE,

If they are external from the MSM chip this driver should probably be renamed
to something more appropriate since it is probably dream specific and not
generic to the msm architecture.

Thanks for the help,
Hartley
????{.n?+???????+%?????ݶ??w??{.n?+????{??G?????{ay?ʇڙ?,j??f???h?????????z_??(?階?ݢj"???m??????G????????????&???~???iO???z??v?^?m???? ????????I?

2009-12-14 19:00:41

by Hartley Sweeten

[permalink] [raw]
Subject: RE: GPIO support for HTC Dream

On Sunday, December 13, 2009 11:46 PM, Pavel Machek wrote:

<snip>

> It now looks like this. I still need to test it and clean up
> warnings. (and move those selects)
> Pavel
>
> diff --git a/arch/arm/Kconfig b/arch/arm/Kconfig
> index 1c4119c..8bb8546 100644
> --- a/arch/arm/Kconfig
> +++ b/arch/arm/Kconfig
> @@ -565,6 +565,8 @@ config ARCH_MSM
> select CPU_V6
> select GENERIC_TIME
> select GENERIC_CLOCKEVENTS
> + select GENERIC_GPIO
> + select ARCH_REQUIRE_GPIOLIB
> help
> Support for Qualcomm MSM7K based systems. This runs on the ARM11
> apps processor of the MSM7K and depends on a shared memory
> diff --git a/arch/arm/mach-msm/Makefile b/arch/arm/mach-msm/Makefile
> index 91e6f5c..4c2567e 100644
> --- a/arch/arm/mach-msm/Makefile
> +++ b/arch/arm/mach-msm/Makefile
> @@ -6,4 +6,4 @@ obj-y += clock.o clock-7x01a.o
>
> obj-$(CONFIG_MACH_HALIBUT) += board-halibut.o
>
> -obj-$(CONFIG_MACH_TROUT) += board-dream.o
> +obj-$(CONFIG_MACH_TROUT) += board-dream.o board-dream-gpio.o generic_gpio.o
> diff --git a/arch/arm/mach-msm/board-dream-gpio.c b/arch/arm/mach-msm/board-dream-gpio.c
> new file mode 100644
> index 0000000..4cf6ec0
> --- /dev/null
> +++ b/arch/arm/mach-msm/board-dream-gpio.c
> @@ -0,0 +1,116 @@
> +/*
> + * linux/arch/arm/mach-msm/gpio.c
> + *
> + * Copyright (C) 2005 HP Labs
> + * Copyright (C) 2008 Google, Inc.
> + * Copyright (C) 2009 Pavel Machek <[email protected]>
> + *
> + * This program is free software; you can redistribute it and/or modify
> + * it under the terms of the GNU General Public License as published by
> + * the Free Software Foundation; either version 2 of the License, or
> + * (at your option) any later version.
> + */
> +
> +#include <linux/kernel.h>
> +#include <linux/module.h>
> +#include <linux/io.h>
> +#include <linux/gpio.h>
> +
> +#include "board-dream.h"
> +
> +struct msm_gpio_chip {
> + struct gpio_chip chip;
> + void __iomem *reg; /* Base of register bank */
> + u8 shadow;
> +};
> +
> +#define to_msm_gpio_chip(c) container_of(c, struct msm_gpio_chip, chip)
> +
> +static int msm_gpiolib_get(struct gpio_chip *chip, unsigned offset)
> +{
> + struct msm_gpio_chip *msm_gpio = to_msm_gpio_chip(chip);
> + unsigned mask = 1 << offset;
> +
> + return !! (readb(msm_gpio->reg) & mask);
> +}
> +
> +static void msm_gpiolib_set(struct gpio_chip *chip, unsigned offset, int val)
> +{
> + struct msm_gpio_chip *msm_gpio = to_msm_gpio_chip(chip);
> + unsigned mask = 1 << offset;
> +
> + if (val)
> + msm_gpio->shadow |= mask;
> + else
> + msm_gpio->shadow &= ~mask;
> +
> + writeb(msm_gpio->shadow, msm_gpio->reg);
> +}
> +
> +static int msm_gpiolib_direction_input(struct gpio_chip *chip,
> + unsigned offset)
> +{
> + msm_gpiolib_set(chip, offset, 0);
> + return 0;
> +}
> +
> +static int msm_gpiolib_direction_output(struct gpio_chip *chip,
> + unsigned offset, int val)
> +{
> + msm_gpiolib_set(chip, offset, val);
> + return 0;
> +}
> +
> +int gpio_to_irq(unsigned gpio)
> +{
> + return -EINVAL;
> +}

This should probably just be an inline function in
arch/arm/mach-msm/include/mach/gpio.h

> +
> +#define DREAM_GPIO_BANK(name, reg_num, base_gpio, shadow_val) \
> + { \
> + .chip = { \
> + .label = name, \
> + .direction_input = msm_gpiolib_direction_input, \
> + .direction_output = msm_gpiolib_direction_output, \
> + .get = msm_gpiolib_get, \
> + .set = msm_gpiolib_set, \
> + .base = base_gpio, \
> + .ngpio = 8, \
> + }, \
> + .reg = reg_num + DREAM_CPLD_BASE, \
> + .shadow = shadow_val, \
> + }
> +
> +static struct msm_gpio_chip msm_gpio_banks[] = {
> +#if defined(CONFIG_MSM_DEBUG_UART1)
> + /* H2W pins <-> UART1 */
> + DREAM_GPIO_BANK("MISC2", 0x00, DREAM_GPIO_MISC2_BASE, 0x40),
> +#else
> + /* H2W pins <-> UART3, Bluetooth <-> UART1 */
> + DREAM_GPIO_BANK("MISC2", 0x00, DREAM_GPIO_MISC2_BASE, 0x80),
> +#endif
> + /* I2C pull */
> + DREAM_GPIO_BANK("MISC3", 0x02, DREAM_GPIO_MISC3_BASE, 0x04),
> + DREAM_GPIO_BANK("MISC4", 0x04, DREAM_GPIO_MISC4_BASE, 0),
> + /* mmdi 32k en */
> + DREAM_GPIO_BANK("MISC5", 0x06, DREAM_GPIO_MISC5_BASE, 0x04),
> + DREAM_GPIO_BANK("INT2", 0x08, DREAM_GPIO_INT2_BASE, 0),
> + DREAM_GPIO_BANK("MISC1", 0x0a, DREAM_GPIO_MISC1_BASE, 0),
> + DREAM_GPIO_BANK("VIRTUAL", 0x12, DREAM_GPIO_VIRTUAL_BASE, 0),
> +};
> +
> +/*
> + * Called from the processor-specific init to enable GPIO pin support.
> + */
> +int __init dream_init_gpio(void)
> +{
> + int i;
> +
> + for (i = 0; i < ARRAY_SIZE(msm_gpio_banks); i++)
> + gpiochip_add(&msm_gpio_banks[i].chip);
> +
> + return 0;
> +}
> +
> +postcore_initcall(dream_init_gpio);
> +
> diff --git a/arch/arm/mach-msm/board-dream.h b/arch/arm/mach-msm/board-dream.h
> index 4f345a5..dbd78b9 100644
> --- a/arch/arm/mach-msm/board-dream.h
> +++ b/arch/arm/mach-msm/board-dream.h
> @@ -1,5 +1,58 @@
>
> -#define TROUT_CPLD_BASE 0xE8100000
> -#define TROUT_CPLD_START 0x98000000
> -#define TROUT_CPLD_SIZE SZ_4K
> +#define MSM_SMI_BASE 0x00000000
> +#define MSM_SMI_SIZE 0x00800000
> +
> +#define MSM_EBI_BASE 0x10000000
> +#define MSM_EBI_SIZE 0x06e00000
> +
> +#define MSM_PMEM_GPU0_BASE 0x00000000
> +#define MSM_PMEM_GPU0_SIZE 0x00700000
> +
> +#define MSM_PMEM_MDP_BASE 0x02000000
> +#define MSM_PMEM_MDP_SIZE 0x00800000
> +
> +#define MSM_PMEM_ADSP_BASE 0x02800000
> +#define MSM_PMEM_ADSP_SIZE 0x00800000
> +
> +#define MSM_PMEM_CAMERA_BASE 0x03000000
> +#define MSM_PMEM_CAMERA_SIZE 0x00800000
> +
> +#define MSM_FB_BASE 0x03800000
> +#define MSM_FB_SIZE 0x00100000
> +
> +#define MSM_LINUX_BASE MSM_EBI_BASE
> +#define MSM_LINUX_SIZE 0x06500000
> +
> +#define MSM_PMEM_GPU1_SIZE 0x800000
> +#define MSM_PMEM_GPU1_BASE (MSM_RAM_CONSOLE_BASE - MSM_PMEM_GPU1_SIZE)
> +
> +#define MSM_RAM_CONSOLE_BASE (MSM_EBI_BASE + 0x6d00000)
> +#define MSM_RAM_CONSOLE_SIZE (128 * SZ_1K)
> +
> +#if (MSM_FB_BASE + MSM_FB_SIZE) >= (MSM_PMEM_GPU1_BASE)
> +#error invalid memory map
> +#endif
> +
> +#define DECLARE_MSM_IOMAP
> +#include <mach/msm_iomap.h>
> +
> +#define DREAM_4_BALL_UP_0 1
> +#define DREAM_4_BALL_LEFT_0 18
> +#define DREAM_4_BALL_DOWN_0 57
> +#define DREAM_4_BALL_RIGHT_0 91
> +
> +#define DREAM_5_BALL_UP_0 94
> +#define DREAM_5_BALL_LEFT_0 18
> +#define DREAM_5_BALL_DOWN_0 90
> +#define DREAM_5_BALL_RIGHT_0 19
> +
> +#define DREAM_POWER_KEY 20
> +
> +#define DREAM_4_TP_LS_EN 19
> +#define DREAM_5_TP_LS_EN 1
> +
> +#define DREAM_CPLD_BASE 0xE8100000
> +#define DREAM_CPLD_START 0x98000000
> +#define DREAM_CPLD_SIZE SZ_4K
> +

This header might need to be a separate patch. The only thing in it
related to the rest of this is DREAM_CPLD_BASE.

> diff --git a/arch/arm/mach-msm/generic_gpio.c b/arch/arm/mach-msm/generic_gpio.c
> new file mode 100644
> index 0000000..357e63e
> --- /dev/null
> +++ b/arch/arm/mach-msm/generic_gpio.c
> @@ -0,0 +1,15 @@
> +/* arch/arm/mach-msm/generic_gpio.c
> + *
> + * Copyright (C) 2007 Google, Inc.
> + *
> + * This software is licensed under the terms of the GNU General Public
> + * License version 2, as published by the Free Software Foundation, and
> + * may be copied, distributed, and modified under those terms.
> + *
> + * This program is distributed in the hope that 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.
> + *
> + */
> +

Is this header really needed?

> diff --git a/arch/arm/mach-msm/gpio_chip.h b/arch/arm/mach-msm/gpio_chip.h
> new file mode 100644
> index 0000000..ffc4d54
> --- /dev/null
> +++ b/arch/arm/mach-msm/gpio_chip.h
> @@ -0,0 +1,20 @@
> +/* arch/arm/mach-msm/gpio_chip.h
> + *
> + * Copyright (C) 2007 Google, Inc.
> + *
> + * This software is licensed under the terms of the GNU General Public
> + * License version 2, as published by the Free Software Foundation, and
> + * may be copied, distributed, and modified under those terms.
> + *
> + * This program is distributed in the hope that 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.
> + *
> + */
> +
> +#ifndef _LINUX_GPIO_CHIP_H
> +#define _LINUX_GPIO_CHIP_H
> +
> +
> +#endif

Same with this one?

> diff --git a/arch/arm/mach-msm/include/mach/gpio.h b/arch/arm/mach-msm/include/mach/gpio.h
> new file mode 100644
> index 0000000..e92bc31
> --- /dev/null
> +++ b/arch/arm/mach-msm/include/mach/gpio.h
> @@ -0,0 +1,105 @@
> +/*
> + * Copyright (C) 2007 Google, Inc.
> + * Author: Mike Lockwood <[email protected]>
> + * Copyright (C) 2009 Pavel Machek <[email protected]>
> + *
> + * This software is licensed under the terms of the GNU General Public
> + * License version 2, as published by the Free Software Foundation, and
> + * may be copied, distributed, and modified under those terms.
> + *
> + * This program is distributed in the hope that 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.
> + *
> + */
> +
> +#ifndef __ASM_ARCH_MSM_GPIO_H
> +#define __ASM_ARCH_MSM_GPIO_H
> +
> +extern int gpio_to_irq(unsigned gpio);

This should probably be an inline as mentioned above.

For completeness you should probably also add:

static inline int irq_to_gpio(unsigned irq)
{
return -EINVAL;
}

And, nitpick, move both of them after the gpio_cansleep below.

> +
> +#include <asm-generic/gpio.h>
> +
> +#define gpio_get_value __gpio_get_value
> +#define gpio_set_value __gpio_set_value
> +#define gpio_cansleep __gpio_cansleep
> +
> +#define DREAM_GPIO_CABLE_IN1 (83)
> +#define DREAM_GPIO_CABLE_IN2 (49)
> +
> +#define DREAM_GPIO_START (128)

Nitpick. Tab align these three with the ones below.

> +
> +#define DREAM_GPIO_INT_MASK0_REG (0x0c)
> +#define DREAM_GPIO_INT_STAT0_REG (0x0e)
> +#define DREAM_GPIO_INT_MASK1_REG (0x14)
> +#define DREAM_GPIO_INT_STAT1_REG (0x10)
> +
> +#define DREAM_GPIO_HAPTIC_PWM (28)
> +#define DREAM_GPIO_PS_HOLD (25)
> +
> +#define DREAM_GPIO_MISC2_BASE (DREAM_GPIO_START + 0x00)
> +#define DREAM_GPIO_MISC3_BASE (DREAM_GPIO_START + 0x08)
> +#define DREAM_GPIO_MISC4_BASE (DREAM_GPIO_START + 0x10)
> +#define DREAM_GPIO_MISC5_BASE (DREAM_GPIO_START + 0x18)
> +#define DREAM_GPIO_INT2_BASE (DREAM_GPIO_START + 0x20)
> +#define DREAM_GPIO_MISC1_BASE (DREAM_GPIO_START + 0x28)
> +#define DREAM_GPIO_VIRTUAL_BASE (DREAM_GPIO_START + 0x30)
> +#define DREAM_GPIO_INT5_BASE (DREAM_GPIO_START + 0x48)
> +
> +#define DREAM_GPIO_CHARGER_EN (DREAM_GPIO_MISC2_BASE + 0)
> +#define DREAM_GPIO_ISET (DREAM_GPIO_MISC2_BASE + 1)
> +#define DREAM_GPIO_H2W_DAT_DIR (DREAM_GPIO_MISC2_BASE + 2)
> +#define DREAM_GPIO_H2W_CLK_DIR (DREAM_GPIO_MISC2_BASE + 3)
> +#define DREAM_GPIO_H2W_DAT_GPO (DREAM_GPIO_MISC2_BASE + 4)
> +#define DREAM_GPIO_H2W_CLK_GPO (DREAM_GPIO_MISC2_BASE + 5)
> +#define DREAM_GPIO_H2W_SEL0 (DREAM_GPIO_MISC2_BASE + 6)
> +#define DREAM_GPIO_H2W_SEL1 (DREAM_GPIO_MISC2_BASE + 7)
> +
> +#define DREAM_GPIO_SPOTLIGHT_EN (DREAM_GPIO_MISC3_BASE + 0)
> +#define DREAM_GPIO_FLASH_EN (DREAM_GPIO_MISC3_BASE + 1)
> +#define DREAM_GPIO_I2C_PULL (DREAM_GPIO_MISC3_BASE + 2)
> +#define DREAM_GPIO_TP_I2C_PULL (DREAM_GPIO_MISC3_BASE + 3)
> +#define DREAM_GPIO_TP_EN (DREAM_GPIO_MISC3_BASE + 4)
> +#define DREAM_GPIO_JOG_EN (DREAM_GPIO_MISC3_BASE + 5)
> +#define DREAM_GPIO_UI_LED_EN (DREAM_GPIO_MISC3_BASE + 6)
> +#define DREAM_GPIO_QTKEY_LED_EN (DREAM_GPIO_MISC3_BASE + 7)
> +
> +#define DREAM_GPIO_VCM_PWDN (DREAM_GPIO_MISC4_BASE + 0)
> +#define DREAM_GPIO_USB_H2W_SW (DREAM_GPIO_MISC4_BASE + 1)
> +#define DREAM_GPIO_COMPASS_RST_N (DREAM_GPIO_MISC4_BASE + 2)
> +#define DREAM_GPIO_HAPTIC_EN_UP (DREAM_GPIO_MISC4_BASE + 3)
> +#define DREAM_GPIO_HAPTIC_EN_MAIN (DREAM_GPIO_MISC4_BASE + 4)
> +#define DREAM_GPIO_USB_PHY_RST_N (DREAM_GPIO_MISC4_BASE + 5)
> +#define DREAM_GPIO_WIFI_PA_RESETX (DREAM_GPIO_MISC4_BASE + 6)
> +#define DREAM_GPIO_WIFI_EN (DREAM_GPIO_MISC4_BASE + 7)
> +
> +#define DREAM_GPIO_BT_32K_EN (DREAM_GPIO_MISC5_BASE + 0)
> +#define DREAM_GPIO_MAC_32K_EN (DREAM_GPIO_MISC5_BASE + 1)
> +#define DREAM_GPIO_MDDI_32K_EN (DREAM_GPIO_MISC5_BASE + 2)
> +#define DREAM_GPIO_COMPASS_32K_EN (DREAM_GPIO_MISC5_BASE + 3)
> +
> +#define DREAM_GPIO_NAVI_ACT_N (DREAM_GPIO_INT2_BASE + 0)
> +#define DREAM_GPIO_COMPASS_IRQ (DREAM_GPIO_INT2_BASE + 1)
> +#define DREAM_GPIO_SLIDING_DET (DREAM_GPIO_INT2_BASE + 2)
> +#define DREAM_GPIO_AUD_HSMIC_DET_N (DREAM_GPIO_INT2_BASE + 3)
> +#define DREAM_GPIO_SD_DOOR_N (DREAM_GPIO_INT2_BASE + 4)
> +#define DREAM_GPIO_CAM_BTN_STEP1_N (DREAM_GPIO_INT2_BASE + 5)
> +#define DREAM_GPIO_CAM_BTN_STEP2_N (DREAM_GPIO_INT2_BASE + 6)
> +#define DREAM_GPIO_TP_ATT_N (DREAM_GPIO_INT2_BASE + 7)
> +#define DREAM_GPIO_BANK0_FIRST_INT_SOURCE (DREAM_GPIO_NAVI_ACT_N)
> +#define DREAM_GPIO_BANK0_LAST_INT_SOURCE (DREAM_GPIO_TP_ATT_N)
> +
> +#define DREAM_GPIO_H2W_DAT_GPI (DREAM_GPIO_MISC1_BASE + 0)
> +#define DREAM_GPIO_H2W_CLK_GPI (DREAM_GPIO_MISC1_BASE + 1)
> +#define DREAM_GPIO_CPLD128_VER_0 (DREAM_GPIO_MISC1_BASE + 4)
> +#define DREAM_GPIO_CPLD128_VER_1 (DREAM_GPIO_MISC1_BASE + 5)
> +#define DREAM_GPIO_CPLD128_VER_2 (DREAM_GPIO_MISC1_BASE + 6)
> +#define DREAM_GPIO_CPLD128_VER_3 (DREAM_GPIO_MISC1_BASE + 7)
> +
> +#define DREAM_GPIO_SDMC_CD_N (DREAM_GPIO_VIRTUAL_BASE + 0)
> +#define DREAM_GPIO_END (DREAM_GPIO_SDMC_CD_N)
> +#define DREAM_GPIO_BANK1_FIRST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
> +#define DREAM_GPIO_BANK1_LAST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
> +
> +#endif

Otherwise, looks good to me. Just test it to make sure it works :-).

Since I have no way of compiling or testing this...

Reviewed-by: H Hartley Sweeten <[email protected]>

Regards,
Hartley

2009-12-15 06:40:27

by Arve Hjønnevåg

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Mon, Dec 14, 2009 at 10:12 AM, H Hartley Sweeten
<[email protected]> wrote:
> On Monday, December 14, 2009 10:55 AM, Daniel Walker wrote:
>> On Mon, 2009-12-14 at 07:45 +0100, Pavel Machek wrote:
>>> Hi!
>>>
>>>> This looks MUCH better!
>>>
>>> Thanks :-).
>>>
>>>>> arch/arm/Kconfig ? ? ? ? ? ? ? ? ? ? | ? ?1
>>>>> arch/arm/mach-msm/board-dream-gpio.c | ?327 +++++++++--------------------------
>>> ...
>>>> Please update (or remove) this diffstat. ?It no longer matches the patch.
>>>
>>> I was just showing differences to _previous_ version, not what I was sending.
>>>
>>>> Ok. ?The hardware still seems a bit strange. Is there any datasheet
>>>> available?
>>>
>>> I don't think there is one. Daniel, can you help here?
>>
>> I don't know if there is one or not (I'd guess not).. I can't release
>> documents, but I could try to address specific questions or find people
>> to answer specific questions.
>
> Hello Daniel,
>
> My specific question was about the gpio hardware registers.
>
> From Pavel's implementation it appears that the gpio's are organized as a
> number of 8-bit ports. ?Each of these ports only have one 8-bit register.
> Writing a '1' to a bit in the register makes the associated pin a high-level
> output. ?Writing a '0' makes the pin a low-level output or an input pin.
> Reading the port at this point will return the actual 'input' level of the pin.
>
> The hardware seems a bit strange and I just wanted to verify that this is
> correct. ?If it is, this would explain the need to keep the 'shadow' contents
> of the port in order to set the 'direction' of a pin.
>
> I was also wondering if the initial 'shadow' value needs to be written to the
> port at init in order to correctly establish the output value for specific
> pins.
>
> One other thing. ?Are the gpio's handled by Pavel's driver actually from the
> MSM chip or from an external CPLD? ?The registers are all defined as:
>
> + ? ? ? ? ? ? ? .reg = reg_num + DREAM_CPLD_BASE,
>
> If they are external from the MSM chip this driver should probably be renamed
> to something more appropriate since it is probably dream specific and not
> generic to the msm architecture.

These are board specific gpios. I think it would be less confusing if
the msm gpio support was added first.

--
Arve Hj?nnev?g

2009-12-15 06:48:06

by Arve Hjønnevåg

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Sun, Dec 13, 2009 at 10:45 PM, Pavel Machek <[email protected]> wrote:
>> > +int __init dream_init_gpio(void)
>> > +{
>> > + ? ? ? ?int i;
>> > +
>> > + ? ? ? ?for (i = 0; i < ARRAY_SIZE(msm_gpio_banks); i++)
>> > + ? ? ? ? ? ? ? ?gpiochip_add(&msm_gpio_banks[i].chip);
>> > +
>> > + ? return 0;
>> > +}
>>
>> Your original patch was initially writing the shadow values to the registers.
>> Do you still need to do that?
>
> It seems to boot this way :-). If writing the shadow values is not
> needed, lets try getting away without it...

I may boot this way, but unless you know that the bootloader
initialized all the registers to the same value, some outputs will be
in the wrong state until someone writes to a gpio in the same bank.

--
Arve Hj?nnev?g

2009-12-15 19:09:39

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Sun 2009-12-13 13:38:16, Brian Swetland wrote:
> On Sun, Dec 13, 2009 at 1:29 PM, Pavel Machek <[email protected]> wrote:
> >>
> >> I'm going to end up pulling a lot of these git commit into my git tree.
> >> It would be pretty easy for me to just pull this GPIO change directly ..
> >> I assume you haven't found a way to work with git that suites you? It
> >> would be best if you used git, but I could try to do some sort of quilt
> >> export if that works better for you.
> >
> > I can easily "pull" git trees. I do my own work in git, but usually
> > not in a way that would be useful for pushing upstream (see my trees
> > at git.kernel.org).
> >
> > I *could* add my dream trees to those that are mirrored at kernel.org,
> > when things settle a bit. (Should I?)
> >
> > But I'd really prefer to push my stuff using plain old patches in
> > emails.
>
> It would probably be helpful for those of us at Google and Qualcomm,
> who have an entirely git-based workflow to be able to pull patches
> from somewhere, especially if you already have trees that you could
> publish and it's not a huge burden on you.

I do have git trees, but you do not want to pull from them. Getting
the trees into state where you'd want to pull from them would be quite
hard.

> What has worked well for me the last couple times I've sent patches
> out was to put them in an outgoing git branch somewhere, use the git
> tools to email them to lkml/lakml for review, and include a pointer to
> the git://... that people can pull from -- sorta the best of both
> worlds.

Well, I guess dwalker's tree can serve as a clean/easy place to pull
from.

Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-15 19:11:01

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Mon 2009-12-14 09:40:55, Daniel Walker wrote:
> On Sun, 2009-12-13 at 22:29 +0100, Pavel Machek wrote:
>
> > > I'm going to end up pulling a lot of these git commit into my git tree.
> > > It would be pretty easy for me to just pull this GPIO change directly ..
> > > I assume you haven't found a way to work with git that suites you? It
> > > would be best if you used git, but I could try to do some sort of quilt
> > > export if that works better for you.
> >
> > I can easily "pull" git trees. I do my own work in git, but usually
> > not in a way that would be useful for pushing upstream (see my trees
> > at git.kernel.org).
> >
> > I *could* add my dream trees to those that are mirrored at kernel.org,
> > when things settle a bit. (Should I?)
>
> I'm not sure I know what you mean .. What benefit would that have?

Very little benefit. Remote backup for me, chance to look into my
patches in progress for you.

> > But I'd really prefer to push my stuff using plain old patches in
> > emails.
>
> What I was meaning is you need to keep track of my tree via git, just so
> you know what's going into it and can work off it. If your already doing
> that, then no problem ..

Yes, I can pull easily, so all is well.
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-15 19:12:44

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

> > One other thing. ?Are the gpio's handled by Pavel's driver actually from the
> > MSM chip or from an external CPLD? ?The registers are all defined as:
> >
> > + ? ? ? ? ? ? ? .reg = reg_num + DREAM_CPLD_BASE,
> >
> > If they are external from the MSM chip this driver should probably be renamed
> > to something more appropriate since it is probably dream specific and not
> > generic to the msm architecture.
>
> These are board specific gpios. I think it would be less confusing if
> the msm gpio support was added first.

I did not see msm-generic gpios in the trees, where are they? What is
connected over them?
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-15 19:47:37

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

Hi!

> > +int gpio_to_irq(unsigned gpio)
> > +{
> > + return -EINVAL;
> > +}
>
> This should probably just be an inline function in
> arch/arm/mach-msm/include/mach/gpio.h

Well, it is not performance critical in any way and it is likely to
change in future. I'd leave it here.

> > diff --git a/arch/arm/mach-msm/board-dream.h b/arch/arm/mach-msm/board-dream.h
> > index 4f345a5..dbd78b9 100644
> > --- a/arch/arm/mach-msm/board-dream.h
> > +++ b/arch/arm/mach-msm/board-dream.h
> > @@ -1,5 +1,58 @@
> >
> > -#define TROUT_CPLD_BASE 0xE8100000
> > -#define TROUT_CPLD_START 0x98000000
> > -#define TROUT_CPLD_SIZE SZ_4K
> > +#define MSM_SMI_BASE 0x00000000
> > +#define MSM_SMI_SIZE 0x00800000
...
> > +#define DREAM_CPLD_BASE 0xE8100000
> > +#define DREAM_CPLD_START 0x98000000
> > +#define DREAM_CPLD_SIZE SZ_4K
> > +
>
> This header might need to be a separate patch. The only thing in it
> related to the rest of this is DREAM_CPLD_BASE.

Yep.

> > +#ifndef __ASM_ARCH_MSM_GPIO_H
> > +#define __ASM_ARCH_MSM_GPIO_H
> > +
> > +extern int gpio_to_irq(unsigned gpio);
>
> This should probably be an inline as mentioned above.
>
> For completeness you should probably also add:
>
> static inline int irq_to_gpio(unsigned irq)
> {
> return -EINVAL;
> }

I'd say that would be overdoing it.

> And, nitpick, move both of them after the gpio_cansleep below.

I'll do the move.

> > +#define DREAM_GPIO_CABLE_IN1 (83)
> > +#define DREAM_GPIO_CABLE_IN2 (49)
> > +
> > +#define DREAM_GPIO_START (128)
>
> Nitpick. Tab align these three with the ones below.

Ok.

> > +#define DREAM_GPIO_SDMC_CD_N (DREAM_GPIO_VIRTUAL_BASE + 0)
> > +#define DREAM_GPIO_END (DREAM_GPIO_SDMC_CD_N)
> > +#define DREAM_GPIO_BANK1_FIRST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
> > +#define DREAM_GPIO_BANK1_LAST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
> > +
> > +#endif
>
> Otherwise, looks good to me. Just test it to make sure it works :-).
>
> Since I have no way of compiling or testing this...
>
> Reviewed-by: H Hartley Sweeten <[email protected]>

I believe inlining that function would be bad change. Can I still use
reviewed-by tag?
Pavel

--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-15 20:28:12

by Daniel Walker

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Tue, 2009-12-15 at 20:12 +0100, Pavel Machek wrote:
> > > One other thing. Are the gpio's handled by Pavel's driver actually from the
> > > MSM chip or from an external CPLD? The registers are all defined as:
> > >
> > > + .reg = reg_num + DREAM_CPLD_BASE,
> > >
> > > If they are external from the MSM chip this driver should probably be renamed
> > > to something more appropriate since it is probably dream specific and not
> > > generic to the msm architecture.
> >
> > These are board specific gpios. I think it would be less confusing if
> > the msm gpio support was added first.
>
> I did not see msm-generic gpios in the trees, where are they? What is
> connected over them?

Did you look at arch/arm/mach-msm/gpio.[ch] ? It looks like there some
idle related code in there, and "SMEM" is connected through that code.
(unless I'm looking at an older tree.)

Daniel

2009-12-15 20:15:18

by Hartley Sweeten

[permalink] [raw]
Subject: RE: GPIO support for HTC Dream

On Tuesday, December 15, 2009 12:47 PM, Pavel Machek wrote:
>
> Hi!
>
>>> +int gpio_to_irq(unsigned gpio)
>>> +{
>>> + return -EINVAL;
>>> +}
>>
>> This should probably just be an inline function in
>> arch/arm/mach-msm/include/mach/gpio.h
>
> Well, it is not performance critical in any way and it is likely to
> change in future. I'd leave it here.

Comment below..

>>> diff --git a/arch/arm/mach-msm/board-dream.h b/arch/arm/mach-msm/board-dream.h
>>> index 4f345a5..dbd78b9 100644
>>> --- a/arch/arm/mach-msm/board-dream.h
>>> +++ b/arch/arm/mach-msm/board-dream.h
>>> @@ -1,5 +1,58 @@
>>>
>>> -#define TROUT_CPLD_BASE 0xE8100000
>>> -#define TROUT_CPLD_START 0x98000000
>>> -#define TROUT_CPLD_SIZE SZ_4K
>>> +#define MSM_SMI_BASE 0x00000000
>>> +#define MSM_SMI_SIZE 0x00800000
...
>>> +#define DREAM_CPLD_BASE 0xE8100000
>>> +#define DREAM_CPLD_START 0x98000000
>>> +#define DREAM_CPLD_SIZE SZ_4K
>>> +
>>
>> This header might need to be a separate patch. The only thing in it
>> related to the rest of this is DREAM_CPLD_BASE.
>
> Yep.
>
>>> +#ifndef __ASM_ARCH_MSM_GPIO_H
>>> +#define __ASM_ARCH_MSM_GPIO_H
>>> +
>>> +extern int gpio_to_irq(unsigned gpio);
>>
>> This should probably be an inline as mentioned above.
>>
>> For completeness you should probably also add:
>>
>> static inline int irq_to_gpio(unsigned irq)
>> {
>> return -EINVAL;
>> }
>
> I'd say that would be overdoing it.

I only mentioned that one because it is one of the functions listed in
Documentation/gpio.txt. I'm not sure if that means it's "required". You
make the call...

>> And, nitpick, move both of them after the gpio_cansleep below.
>
> I'll do the move.
>
>>> +#define DREAM_GPIO_CABLE_IN1 (83)
>>> +#define DREAM_GPIO_CABLE_IN2 (49)
>>> +
>>> +#define DREAM_GPIO_START (128)
>>
>> Nitpick. Tab align these three with the ones below.
>
> Ok.
>
>>> +#define DREAM_GPIO_SDMC_CD_N (DREAM_GPIO_VIRTUAL_BASE + 0)
>>> +#define DREAM_GPIO_END (DREAM_GPIO_SDMC_CD_N)
>>> +#define DREAM_GPIO_BANK1_FIRST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
>>> +#define DREAM_GPIO_BANK1_LAST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
>>> +
>>> +#endif
>>
>> Otherwise, looks good to me. Just test it to make sure it works :-).
>>
>> Since I have no way of compiling or testing this...
>>
>> Reviewed-by: H Hartley Sweeten <[email protected]>
>
> I believe inlining that function would be bad change. Can I still use
> reviewed-by tag?

The reason I suggest making it an inline in the header is you might
eventually want to change both gpio_to_irq and irq_to_gpio into macros
so that they can be used for static initializers. For right now both
are simple return -EINVAL but when gpio irq's are supported you might
find a need to use one or the other in a platform init...

Regardless, yes you can still use my reviesed-by tag.

Regards,
Hartley

2009-12-15 20:23:50

by Ryan Mallon

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

Pavel Machek wrote:
> Hi!
>
>>> +int gpio_to_irq(unsigned gpio)
>>> +{
>>> + return -EINVAL;
>>> +}
>> This should probably just be an inline function in
>> arch/arm/mach-msm/include/mach/gpio.h
>
> Well, it is not performance critical in any way and it is likely to
> change in future. I'd leave it here.

If this function eventually does do something interesting, it would be
useful to have it as a macro in arch/arm/mach-msm/include/mach/gpio.h
since it can be used for static/define declarations, ie:

#define SOME_GPIO_IRQ gpio_to_irq(SOME_GPIO)

>>> +extern int gpio_to_irq(unsigned gpio);
>> This should probably be an inline as mentioned above.
>>
>> For completeness you should probably also add:
>>
>> static inline int irq_to_gpio(unsigned irq)
>> {
>> return -EINVAL;
>> }
>
> I'd say that would be overdoing it.

You should implement this if you have gpio_to_irq because it is part of
the API, see include/linux/gpio.h

~Ryan

--
Bluewater Systems Ltd - ARM Technology Solution Centre

Ryan Mallon 5 Amuri Park, 404 Barbadoes St
[email protected] PO Box 13 889, Christchurch 8013
http://www.bluewatersys.com New Zealand
Phone: +64 3 3779127 Freecall: Australia 1800 148 751
Fax: +64 3 3779135 USA 1800 261 2934

2009-12-15 20:45:09

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Wed 2009-12-16 09:24:21, Ryan Mallon wrote:
> Pavel Machek wrote:
> > Hi!
> >
> >>> +int gpio_to_irq(unsigned gpio)
> >>> +{
> >>> + return -EINVAL;
> >>> +}
> >> This should probably just be an inline function in
> >> arch/arm/mach-msm/include/mach/gpio.h
> >
> > Well, it is not performance critical in any way and it is likely to
> > change in future. I'd leave it here.
>
> If this function eventually does do something interesting, it would be
> useful to have it as a macro in arch/arm/mach-msm/include/mach/gpio.h
> since it can be used for static/define declarations, ie:
>
> #define SOME_GPIO_IRQ gpio_to_irq(SOME_GPIO)

gpio_to_irq is defined as a function in Doc*/gpio.txt.

> >> static inline int irq_to_gpio(unsigned irq)
> >> {
> >> return -EINVAL;
> >> }
> >
> > I'd say that would be overdoing it.
>
> You should implement this if you have gpio_to_irq because it is part of
> the API, see include/linux/gpio.h

I'm implementing it. I just don't want to implement two inline
functions instead of one normal function.
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-15 20:47:59

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

Hi!

> >> For completeness you should probably also add:
> >>
> >> static inline int irq_to_gpio(unsigned irq)
> >> {
> >> return -EINVAL;
> >> }
> >
> > I'd say that would be overdoing it.
>
> I only mentioned that one because it is one of the functions listed in
> Documentation/gpio.txt. I'm not sure if that means it's "required". You
> make the call...

Aha, sorry, I misparsed that. There's gpio_to_irq and irq_to_gpio. One
does not seem to be required; as I'm stubbing the other one, I'd
prefer to leave it alone.

> >> Otherwise, looks good to me. Just test it to make sure it works :-).
> >>
> >> Since I have no way of compiling or testing this...
> >>
> >> Reviewed-by: H Hartley Sweeten <[email protected]>
> >
> > I believe inlining that function would be bad change. Can I still use
> > reviewed-by tag?
>
> The reason I suggest making it an inline in the header is you might
> eventually want to change both gpio_to_irq and irq_to_gpio into macros
> so that they can be used for static initializers. For right now both
> are simple return -EINVAL but when gpio irq's are supported you might
> find a need to use one or the other in a platform init...

According to gpio.txt, those are functions, not macros... and I
actually prefer functions, as they are harder to misuse.

> Regardless, yes you can still use my reviesed-by tag.

Thanks.
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-15 20:48:22

by Jamie Lokier

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

H Hartley Sweeten wrote:
> From Pavel's implementation it appears that the gpio's are organized
> as a number of 8-bit ports. Each of these ports only have one 8-bit
> register. Writing a '1' to a bit in the register makes the
> associated pin a high-level output. Writing a '0' makes the pin a
> low-level output or an input pin. Reading the port at this point
> will return the actual 'input' level of the pin.
>
> The hardware seems a bit strange and I just wanted to verify that this is
> correct. If it is, this would explain the need to keep the 'shadow' contents
> of the port in order to set the 'direction' of a pin.

It sounds similar to the PCF8575 (except polarity is reversed), which
is an I2C-driven GPIO chip with "quasi-bidirectional I/O pins", so not
completely weird.

The PCF8575 is more or less an open collector output - it drives a pin
low when 0 is written, and lets it be pulled high by an external
resistor when 1 is written, and reads return the current measured
level. So by writing 1, you can use the pin as an input, or you can
use it as an output by using a pull-up resistor.

However, to complicate matters, when transitioning from 0 to 1, the
PCF8575 briefly drives the output high, to ensure that a pulled up
output has a rapid transition.

Because of that, you *must not* write 0->1 transitions to the PCF8575
for a GPIO that is driven low by something else, unless you want a
current spike. So you can't use it as an open collector bus, for
example, and it's important to maintain a shadow variable so that you
don't write back bit values read from the chip.

(I don't know why they don't just use separate enable and value bits
like everything else, but there you go).

Perhaps the Dream's GPIOs are similar, but with opposite polarity.
If it also has the same transition driving spike, writing a 1->0
transition would be bad for the hardware making the shadow variable
even more important.

> I was also wondering if the initial 'shadow' value needs to be written to the
> port at init in order to correctly establish the output value for specific
> pins.

If it's like the PCF8575, after hard reset the bits will all be
configured in the input state, and rely on external pull-downs to set
bootup values.

-- Jamie

2009-12-15 21:07:21

by Brian Swetland

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Tue, Dec 15, 2009 at 12:48 PM, Jamie Lokier <[email protected]> wrote:
>
> Perhaps the Dream's GPIOs are similar, but with opposite polarity.
> If it also has the same transition driving spike, writing a 1->0
> transition would be bad for the hardware making the shadow variable
> even more important.

Arve will certainly step in if I'm wrong here, but I believe the issue
is that the dream CPLD GPIOs (which is what we're talking about, not
the MSM7K's onboard GPIOs which are more flexible) have no way to read
the set output state back. So, you can't read-modify-write to change
just one of the 8 bits in a given bank. The default mask values in
the android msm tree's trout gpio board files are based on what he
shipping HTC bootloader initializes things to.

Brian

2009-12-15 21:16:52

by Pavel Machek

[permalink] [raw]
Subject: [patch] GPIO support for HTC Dream


Add GPIO support for HTC Dream.

Signed-off-by: Pavel Machek <[email protected]>
Reviewed-by: H Hartley Sweeten <[email protected]>

---

This should be very correct, including some nitpicking.

diff --git a/arch/arm/mach-msm/Kconfig b/arch/arm/mach-msm/Kconfig
index f780086..fab64f1 100644
--- a/arch/arm/mach-msm/Kconfig
+++ b/arch/arm/mach-msm/Kconfig
@@ -36,6 +36,8 @@ config MACH_HALIBUT

config MACH_TROUT
default y
+ select GENERIC_GPIO
+ select ARCH_REQUIRE_GPIOLIB
bool "HTC Dream (aka trout)"
help
Support for the HTC Dream, T-Mobile G1, Android ADP1 devices.
diff --git a/arch/arm/mach-msm/Makefile b/arch/arm/mach-msm/Makefile
index 91e6f5c..595881d 100644
--- a/arch/arm/mach-msm/Makefile
+++ b/arch/arm/mach-msm/Makefile
@@ -6,4 +6,4 @@ obj-y += clock.o clock-7x01a.o

obj-$(CONFIG_MACH_HALIBUT) += board-halibut.o

-obj-$(CONFIG_MACH_TROUT) += board-dream.o
+obj-$(CONFIG_MACH_TROUT) += board-dream.o board-dream-gpio.o
diff --git a/arch/arm/mach-msm/board-dream-gpio.c b/arch/arm/mach-msm/board-dream-gpio.c
new file mode 100644
index 0000000..f5ea3af
--- /dev/null
+++ b/arch/arm/mach-msm/board-dream-gpio.c
@@ -0,0 +1,116 @@
+/*
+ * linux/arch/arm/mach-msm/gpio.c
+ *
+ * Copyright (C) 2005 HP Labs
+ * Copyright (C) 2008 Google, Inc.
+ * Copyright (C) 2009 Pavel Machek <[email protected]>
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ */
+
+#include <linux/kernel.h>
+#include <linux/module.h>
+#include <linux/io.h>
+#include <linux/gpio.h>
+
+#include "board-dream.h"
+
+struct msm_gpio_chip {
+ struct gpio_chip chip;
+ void __iomem *reg; /* Base of register bank */
+ u8 shadow;
+};
+
+#define to_msm_gpio_chip(c) container_of(c, struct msm_gpio_chip, chip)
+
+static int msm_gpiolib_get(struct gpio_chip *chip, unsigned offset)
+{
+ struct msm_gpio_chip *msm_gpio = to_msm_gpio_chip(chip);
+ unsigned mask = 1 << offset;
+
+ return !! (readb(msm_gpio->reg) & mask);
+}
+
+static void msm_gpiolib_set(struct gpio_chip *chip, unsigned offset, int val)
+{
+ struct msm_gpio_chip *msm_gpio = to_msm_gpio_chip(chip);
+ unsigned mask = 1 << offset;
+
+ if (val)
+ msm_gpio->shadow |= mask;
+ else
+ msm_gpio->shadow &= ~mask;
+
+ writeb(msm_gpio->shadow, msm_gpio->reg);
+}
+
+static int msm_gpiolib_direction_input(struct gpio_chip *chip,
+ unsigned offset)
+{
+ msm_gpiolib_set(chip, offset, 0);
+ return 0;
+}
+
+static int msm_gpiolib_direction_output(struct gpio_chip *chip,
+ unsigned offset, int val)
+{
+ msm_gpiolib_set(chip, offset, val);
+ return 0;
+}
+
+int gpio_to_irq(unsigned gpio)
+{
+ return -EINVAL;
+}
+
+#define DREAM_GPIO_BANK(name, reg_num, base_gpio, shadow_val) \
+ { \
+ .chip = { \
+ .label = name, \
+ .direction_input = msm_gpiolib_direction_input,\
+ .direction_output = msm_gpiolib_direction_output, \
+ .get = msm_gpiolib_get, \
+ .set = msm_gpiolib_set, \
+ .base = base_gpio, \
+ .ngpio = 8, \
+ }, \
+ .reg = (void *) reg_num + DREAM_CPLD_BASE, \
+ .shadow = shadow_val, \
+ }
+
+static struct msm_gpio_chip msm_gpio_banks[] = {
+#if defined(CONFIG_MSM_DEBUG_UART1)
+ /* H2W pins <-> UART1 */
+ DREAM_GPIO_BANK("MISC2", 0x00, DREAM_GPIO_MISC2_BASE, 0x40),
+#else
+ /* H2W pins <-> UART3, Bluetooth <-> UART1 */
+ DREAM_GPIO_BANK("MISC2", 0x00, DREAM_GPIO_MISC2_BASE, 0x80),
+#endif
+ /* I2C pull */
+ DREAM_GPIO_BANK("MISC3", 0x02, DREAM_GPIO_MISC3_BASE, 0x04),
+ DREAM_GPIO_BANK("MISC4", 0x04, DREAM_GPIO_MISC4_BASE, 0),
+ /* mmdi 32k en */
+ DREAM_GPIO_BANK("MISC5", 0x06, DREAM_GPIO_MISC5_BASE, 0x04),
+ DREAM_GPIO_BANK("INT2", 0x08, DREAM_GPIO_INT2_BASE, 0),
+ DREAM_GPIO_BANK("MISC1", 0x0a, DREAM_GPIO_MISC1_BASE, 0),
+ DREAM_GPIO_BANK("VIRTUAL", 0x12, DREAM_GPIO_VIRTUAL_BASE, 0),
+};
+
+/*
+ * Called from the processor-specific init to enable GPIO pin support.
+ */
+int __init dream_init_gpio(void)
+{
+ int i;
+
+ for (i = 0; i < ARRAY_SIZE(msm_gpio_banks); i++)
+ gpiochip_add(&msm_gpio_banks[i].chip);
+
+ return 0;
+}
+
+postcore_initcall(dream_init_gpio);
+
diff --git a/arch/arm/mach-msm/include/mach/gpio.h b/arch/arm/mach-msm/include/mach/gpio.h
new file mode 100644
index 0000000..6c07b85
--- /dev/null
+++ b/arch/arm/mach-msm/include/mach/gpio.h
@@ -0,0 +1,106 @@
+/*
+ * Copyright (C) 2007 Google, Inc.
+ * Author: Mike Lockwood <[email protected]>
+ * Copyright (C) 2009 Pavel Machek <[email protected]>
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * This program is distributed in the hope that 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.
+ *
+ */
+
+#ifndef __ASM_ARCH_MSM_GPIO_H
+#define __ASM_ARCH_MSM_GPIO_H
+
+#include <asm-generic/gpio.h>
+
+#define gpio_get_value __gpio_get_value
+#define gpio_set_value __gpio_set_value
+#define gpio_cansleep __gpio_cansleep
+
+extern int gpio_to_irq(unsigned gpio);
+
+
+#define DREAM_GPIO_CABLE_IN1 (83)
+#define DREAM_GPIO_CABLE_IN2 (49)
+
+#define DREAM_GPIO_START (128)
+
+#define DREAM_GPIO_INT_MASK0_REG (0x0c)
+#define DREAM_GPIO_INT_STAT0_REG (0x0e)
+#define DREAM_GPIO_INT_MASK1_REG (0x14)
+#define DREAM_GPIO_INT_STAT1_REG (0x10)
+
+#define DREAM_GPIO_HAPTIC_PWM (28)
+#define DREAM_GPIO_PS_HOLD (25)
+
+#define DREAM_GPIO_MISC2_BASE (DREAM_GPIO_START + 0x00)
+#define DREAM_GPIO_MISC3_BASE (DREAM_GPIO_START + 0x08)
+#define DREAM_GPIO_MISC4_BASE (DREAM_GPIO_START + 0x10)
+#define DREAM_GPIO_MISC5_BASE (DREAM_GPIO_START + 0x18)
+#define DREAM_GPIO_INT2_BASE (DREAM_GPIO_START + 0x20)
+#define DREAM_GPIO_MISC1_BASE (DREAM_GPIO_START + 0x28)
+#define DREAM_GPIO_VIRTUAL_BASE (DREAM_GPIO_START + 0x30)
+#define DREAM_GPIO_INT5_BASE (DREAM_GPIO_START + 0x48)
+
+#define DREAM_GPIO_CHARGER_EN (DREAM_GPIO_MISC2_BASE + 0)
+#define DREAM_GPIO_ISET (DREAM_GPIO_MISC2_BASE + 1)
+#define DREAM_GPIO_H2W_DAT_DIR (DREAM_GPIO_MISC2_BASE + 2)
+#define DREAM_GPIO_H2W_CLK_DIR (DREAM_GPIO_MISC2_BASE + 3)
+#define DREAM_GPIO_H2W_DAT_GPO (DREAM_GPIO_MISC2_BASE + 4)
+#define DREAM_GPIO_H2W_CLK_GPO (DREAM_GPIO_MISC2_BASE + 5)
+#define DREAM_GPIO_H2W_SEL0 (DREAM_GPIO_MISC2_BASE + 6)
+#define DREAM_GPIO_H2W_SEL1 (DREAM_GPIO_MISC2_BASE + 7)
+
+#define DREAM_GPIO_SPOTLIGHT_EN (DREAM_GPIO_MISC3_BASE + 0)
+#define DREAM_GPIO_FLASH_EN (DREAM_GPIO_MISC3_BASE + 1)
+#define DREAM_GPIO_I2C_PULL (DREAM_GPIO_MISC3_BASE + 2)
+#define DREAM_GPIO_TP_I2C_PULL (DREAM_GPIO_MISC3_BASE + 3)
+#define DREAM_GPIO_TP_EN (DREAM_GPIO_MISC3_BASE + 4)
+#define DREAM_GPIO_JOG_EN (DREAM_GPIO_MISC3_BASE + 5)
+#define DREAM_GPIO_UI_LED_EN (DREAM_GPIO_MISC3_BASE + 6)
+#define DREAM_GPIO_QTKEY_LED_EN (DREAM_GPIO_MISC3_BASE + 7)
+
+#define DREAM_GPIO_VCM_PWDN (DREAM_GPIO_MISC4_BASE + 0)
+#define DREAM_GPIO_USB_H2W_SW (DREAM_GPIO_MISC4_BASE + 1)
+#define DREAM_GPIO_COMPASS_RST_N (DREAM_GPIO_MISC4_BASE + 2)
+#define DREAM_GPIO_HAPTIC_EN_UP (DREAM_GPIO_MISC4_BASE + 3)
+#define DREAM_GPIO_HAPTIC_EN_MAIN (DREAM_GPIO_MISC4_BASE + 4)
+#define DREAM_GPIO_USB_PHY_RST_N (DREAM_GPIO_MISC4_BASE + 5)
+#define DREAM_GPIO_WIFI_PA_RESETX (DREAM_GPIO_MISC4_BASE + 6)
+#define DREAM_GPIO_WIFI_EN (DREAM_GPIO_MISC4_BASE + 7)
+
+#define DREAM_GPIO_BT_32K_EN (DREAM_GPIO_MISC5_BASE + 0)
+#define DREAM_GPIO_MAC_32K_EN (DREAM_GPIO_MISC5_BASE + 1)
+#define DREAM_GPIO_MDDI_32K_EN (DREAM_GPIO_MISC5_BASE + 2)
+#define DREAM_GPIO_COMPASS_32K_EN (DREAM_GPIO_MISC5_BASE + 3)
+
+#define DREAM_GPIO_NAVI_ACT_N (DREAM_GPIO_INT2_BASE + 0)
+#define DREAM_GPIO_COMPASS_IRQ (DREAM_GPIO_INT2_BASE + 1)
+#define DREAM_GPIO_SLIDING_DET (DREAM_GPIO_INT2_BASE + 2)
+#define DREAM_GPIO_AUD_HSMIC_DET_N (DREAM_GPIO_INT2_BASE + 3)
+#define DREAM_GPIO_SD_DOOR_N (DREAM_GPIO_INT2_BASE + 4)
+#define DREAM_GPIO_CAM_BTN_STEP1_N (DREAM_GPIO_INT2_BASE + 5)
+#define DREAM_GPIO_CAM_BTN_STEP2_N (DREAM_GPIO_INT2_BASE + 6)
+#define DREAM_GPIO_TP_ATT_N (DREAM_GPIO_INT2_BASE + 7)
+#define DREAM_GPIO_BANK0_FIRST_INT_SOURCE (DREAM_GPIO_NAVI_ACT_N)
+#define DREAM_GPIO_BANK0_LAST_INT_SOURCE (DREAM_GPIO_TP_ATT_N)
+
+#define DREAM_GPIO_H2W_DAT_GPI (DREAM_GPIO_MISC1_BASE + 0)
+#define DREAM_GPIO_H2W_CLK_GPI (DREAM_GPIO_MISC1_BASE + 1)
+#define DREAM_GPIO_CPLD128_VER_0 (DREAM_GPIO_MISC1_BASE + 4)
+#define DREAM_GPIO_CPLD128_VER_1 (DREAM_GPIO_MISC1_BASE + 5)
+#define DREAM_GPIO_CPLD128_VER_2 (DREAM_GPIO_MISC1_BASE + 6)
+#define DREAM_GPIO_CPLD128_VER_3 (DREAM_GPIO_MISC1_BASE + 7)
+
+#define DREAM_GPIO_SDMC_CD_N (DREAM_GPIO_VIRTUAL_BASE + 0)
+#define DREAM_GPIO_END (DREAM_GPIO_SDMC_CD_N)
+#define DREAM_GPIO_BANK1_FIRST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
+#define DREAM_GPIO_BANK1_LAST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
+
+#endif

--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-15 21:21:35

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Tue 2009-12-15 12:07:06, Daniel Walker wrote:
> On Tue, 2009-12-15 at 20:12 +0100, Pavel Machek wrote:
> > > > One other thing. Are the gpio's handled by Pavel's driver actually from the
> > > > MSM chip or from an external CPLD? The registers are all defined as:
> > > >
> > > > + .reg = reg_num + DREAM_CPLD_BASE,
> > > >
> > > > If they are external from the MSM chip this driver should probably be renamed
> > > > to something more appropriate since it is probably dream specific and not
> > > > generic to the msm architecture.
> > >
> > > These are board specific gpios. I think it would be less confusing if
> > > the msm gpio support was added first.
> >
> > I did not see msm-generic gpios in the trees, where are they? What is
> > connected over them?
>
> Did you look at arch/arm/mach-msm/gpio.[ch] ? It looks like there some
> idle related code in there, and "SMEM" is connected through that code.
> (unless I'm looking at an older tree.)

Aha, I see... more gpios. No wonder I had problems with MMC and
framebuffer....

Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-16 22:53:56

by Pavel Machek

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Fri 2009-12-11 18:12:35, H Hartley Sweeten wrote:
> On Friday, December 11, 2009 3:41 PM, Arve Hj?nnev?g wrote:
>
> <snip>
>
> >> Now, it will still need some cleanups -- I'm not sure if gpios are
> >> dream-specific or generic for whole msm.... I kind of assume they
> >> should be generic for msm. Google people, can you help?
> >
> > I'm not exactly sure what you are asking. Gpios in general are not
> > dream specific, the code in board-dream-gpio.c is. Some gpios (e.g.
> > DREAM_4_BALL_UP_0) are used for a dream specific function, but point
> > to a gpio that is generic to the msm architecture.
>
> <snip>
>

> >> +++ b/arch/arm/Kconfig
> >> + ? ? ? select GENERIC_GPIO
> >> + ? ? ? select ARCH_REQUIRE_GPIOLIB
> >
> > Please do not do this in a board specific change. You have not changed
> > the msm generic gpio support to use gpiolib.
>
> Where is the msm tree located? mach-msm in mainline doesn't appea to
> have _any_ gpio support.

Right.

> Is Pavel's implementation generic enough to
> work with any msm based board?

I think so but I'm not sure; thats what I wanted google to
clarify. Lets keep it dream-specific for now...
Pavel

--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-16 23:06:19

by Daniel Walker

[permalink] [raw]
Subject: Re: GPIO support for HTC Dream

On Wed, 2009-12-16 at 23:53 +0100, Pavel Machek wrote:

> > Where is the msm tree located? mach-msm in mainline doesn't appea to
> > have _any_ gpio support.
>
> Right.
>
> > Is Pavel's implementation generic enough to
> > work with any msm based board?
>
> I think so but I'm not sure; thats what I wanted google to
> clarify. Lets keep it dream-specific for now...

I don't think so, since it was something added by HTC.. I'm pretty sure
the generic msm gpio's are accessed differently.

Daniel

2009-12-25 17:10:46

by Pavel Machek

[permalink] [raw]
Subject: Re: [patch] GPIO support for HTC Dream

Hi!

Daniel, can we get it merged? It is perfect(TM) :-).
Pavel

On Tue 2009-12-15 22:16:35, Pavel Machek wrote:
>
> Add GPIO support for HTC Dream.
>
> Signed-off-by: Pavel Machek <[email protected]>
> Reviewed-by: H Hartley Sweeten <[email protected]>
>
> ---
>
> This should be very correct, including some nitpicking.
>
> diff --git a/arch/arm/mach-msm/Kconfig b/arch/arm/mach-msm/Kconfig
> index f780086..fab64f1 100644
> --- a/arch/arm/mach-msm/Kconfig
> +++ b/arch/arm/mach-msm/Kconfig
> @@ -36,6 +36,8 @@ config MACH_HALIBUT
>
> config MACH_TROUT
> default y
> + select GENERIC_GPIO
> + select ARCH_REQUIRE_GPIOLIB
> bool "HTC Dream (aka trout)"
> help
> Support for the HTC Dream, T-Mobile G1, Android ADP1 devices.
> diff --git a/arch/arm/mach-msm/Makefile b/arch/arm/mach-msm/Makefile
> index 91e6f5c..595881d 100644
> --- a/arch/arm/mach-msm/Makefile
> +++ b/arch/arm/mach-msm/Makefile
> @@ -6,4 +6,4 @@ obj-y += clock.o clock-7x01a.o
>
> obj-$(CONFIG_MACH_HALIBUT) += board-halibut.o
>
> -obj-$(CONFIG_MACH_TROUT) += board-dream.o
> +obj-$(CONFIG_MACH_TROUT) += board-dream.o board-dream-gpio.o
> diff --git a/arch/arm/mach-msm/board-dream-gpio.c b/arch/arm/mach-msm/board-dream-gpio.c
> new file mode 100644
> index 0000000..f5ea3af
> --- /dev/null
> +++ b/arch/arm/mach-msm/board-dream-gpio.c
> @@ -0,0 +1,116 @@
> +/*
> + * linux/arch/arm/mach-msm/gpio.c
> + *
> + * Copyright (C) 2005 HP Labs
> + * Copyright (C) 2008 Google, Inc.
> + * Copyright (C) 2009 Pavel Machek <[email protected]>
> + *
> + * This program is free software; you can redistribute it and/or modify
> + * it under the terms of the GNU General Public License as published by
> + * the Free Software Foundation; either version 2 of the License, or
> + * (at your option) any later version.
> + */
> +
> +#include <linux/kernel.h>
> +#include <linux/module.h>
> +#include <linux/io.h>
> +#include <linux/gpio.h>
> +
> +#include "board-dream.h"
> +
> +struct msm_gpio_chip {
> + struct gpio_chip chip;
> + void __iomem *reg; /* Base of register bank */
> + u8 shadow;
> +};
> +
> +#define to_msm_gpio_chip(c) container_of(c, struct msm_gpio_chip, chip)
> +
> +static int msm_gpiolib_get(struct gpio_chip *chip, unsigned offset)
> +{
> + struct msm_gpio_chip *msm_gpio = to_msm_gpio_chip(chip);
> + unsigned mask = 1 << offset;
> +
> + return !! (readb(msm_gpio->reg) & mask);
> +}
> +
> +static void msm_gpiolib_set(struct gpio_chip *chip, unsigned offset, int val)
> +{
> + struct msm_gpio_chip *msm_gpio = to_msm_gpio_chip(chip);
> + unsigned mask = 1 << offset;
> +
> + if (val)
> + msm_gpio->shadow |= mask;
> + else
> + msm_gpio->shadow &= ~mask;
> +
> + writeb(msm_gpio->shadow, msm_gpio->reg);
> +}
> +
> +static int msm_gpiolib_direction_input(struct gpio_chip *chip,
> + unsigned offset)
> +{
> + msm_gpiolib_set(chip, offset, 0);
> + return 0;
> +}
> +
> +static int msm_gpiolib_direction_output(struct gpio_chip *chip,
> + unsigned offset, int val)
> +{
> + msm_gpiolib_set(chip, offset, val);
> + return 0;
> +}
> +
> +int gpio_to_irq(unsigned gpio)
> +{
> + return -EINVAL;
> +}
> +
> +#define DREAM_GPIO_BANK(name, reg_num, base_gpio, shadow_val) \
> + { \
> + .chip = { \
> + .label = name, \
> + .direction_input = msm_gpiolib_direction_input,\
> + .direction_output = msm_gpiolib_direction_output, \
> + .get = msm_gpiolib_get, \
> + .set = msm_gpiolib_set, \
> + .base = base_gpio, \
> + .ngpio = 8, \
> + }, \
> + .reg = (void *) reg_num + DREAM_CPLD_BASE, \
> + .shadow = shadow_val, \
> + }
> +
> +static struct msm_gpio_chip msm_gpio_banks[] = {
> +#if defined(CONFIG_MSM_DEBUG_UART1)
> + /* H2W pins <-> UART1 */
> + DREAM_GPIO_BANK("MISC2", 0x00, DREAM_GPIO_MISC2_BASE, 0x40),
> +#else
> + /* H2W pins <-> UART3, Bluetooth <-> UART1 */
> + DREAM_GPIO_BANK("MISC2", 0x00, DREAM_GPIO_MISC2_BASE, 0x80),
> +#endif
> + /* I2C pull */
> + DREAM_GPIO_BANK("MISC3", 0x02, DREAM_GPIO_MISC3_BASE, 0x04),
> + DREAM_GPIO_BANK("MISC4", 0x04, DREAM_GPIO_MISC4_BASE, 0),
> + /* mmdi 32k en */
> + DREAM_GPIO_BANK("MISC5", 0x06, DREAM_GPIO_MISC5_BASE, 0x04),
> + DREAM_GPIO_BANK("INT2", 0x08, DREAM_GPIO_INT2_BASE, 0),
> + DREAM_GPIO_BANK("MISC1", 0x0a, DREAM_GPIO_MISC1_BASE, 0),
> + DREAM_GPIO_BANK("VIRTUAL", 0x12, DREAM_GPIO_VIRTUAL_BASE, 0),
> +};
> +
> +/*
> + * Called from the processor-specific init to enable GPIO pin support.
> + */
> +int __init dream_init_gpio(void)
> +{
> + int i;
> +
> + for (i = 0; i < ARRAY_SIZE(msm_gpio_banks); i++)
> + gpiochip_add(&msm_gpio_banks[i].chip);
> +
> + return 0;
> +}
> +
> +postcore_initcall(dream_init_gpio);
> +
> diff --git a/arch/arm/mach-msm/include/mach/gpio.h b/arch/arm/mach-msm/include/mach/gpio.h
> new file mode 100644
> index 0000000..6c07b85
> --- /dev/null
> +++ b/arch/arm/mach-msm/include/mach/gpio.h
> @@ -0,0 +1,106 @@
> +/*
> + * Copyright (C) 2007 Google, Inc.
> + * Author: Mike Lockwood <[email protected]>
> + * Copyright (C) 2009 Pavel Machek <[email protected]>
> + *
> + * This software is licensed under the terms of the GNU General Public
> + * License version 2, as published by the Free Software Foundation, and
> + * may be copied, distributed, and modified under those terms.
> + *
> + * This program is distributed in the hope that 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.
> + *
> + */
> +
> +#ifndef __ASM_ARCH_MSM_GPIO_H
> +#define __ASM_ARCH_MSM_GPIO_H
> +
> +#include <asm-generic/gpio.h>
> +
> +#define gpio_get_value __gpio_get_value
> +#define gpio_set_value __gpio_set_value
> +#define gpio_cansleep __gpio_cansleep
> +
> +extern int gpio_to_irq(unsigned gpio);
> +
> +
> +#define DREAM_GPIO_CABLE_IN1 (83)
> +#define DREAM_GPIO_CABLE_IN2 (49)
> +
> +#define DREAM_GPIO_START (128)
> +
> +#define DREAM_GPIO_INT_MASK0_REG (0x0c)
> +#define DREAM_GPIO_INT_STAT0_REG (0x0e)
> +#define DREAM_GPIO_INT_MASK1_REG (0x14)
> +#define DREAM_GPIO_INT_STAT1_REG (0x10)
> +
> +#define DREAM_GPIO_HAPTIC_PWM (28)
> +#define DREAM_GPIO_PS_HOLD (25)
> +
> +#define DREAM_GPIO_MISC2_BASE (DREAM_GPIO_START + 0x00)
> +#define DREAM_GPIO_MISC3_BASE (DREAM_GPIO_START + 0x08)
> +#define DREAM_GPIO_MISC4_BASE (DREAM_GPIO_START + 0x10)
> +#define DREAM_GPIO_MISC5_BASE (DREAM_GPIO_START + 0x18)
> +#define DREAM_GPIO_INT2_BASE (DREAM_GPIO_START + 0x20)
> +#define DREAM_GPIO_MISC1_BASE (DREAM_GPIO_START + 0x28)
> +#define DREAM_GPIO_VIRTUAL_BASE (DREAM_GPIO_START + 0x30)
> +#define DREAM_GPIO_INT5_BASE (DREAM_GPIO_START + 0x48)
> +
> +#define DREAM_GPIO_CHARGER_EN (DREAM_GPIO_MISC2_BASE + 0)
> +#define DREAM_GPIO_ISET (DREAM_GPIO_MISC2_BASE + 1)
> +#define DREAM_GPIO_H2W_DAT_DIR (DREAM_GPIO_MISC2_BASE + 2)
> +#define DREAM_GPIO_H2W_CLK_DIR (DREAM_GPIO_MISC2_BASE + 3)
> +#define DREAM_GPIO_H2W_DAT_GPO (DREAM_GPIO_MISC2_BASE + 4)
> +#define DREAM_GPIO_H2W_CLK_GPO (DREAM_GPIO_MISC2_BASE + 5)
> +#define DREAM_GPIO_H2W_SEL0 (DREAM_GPIO_MISC2_BASE + 6)
> +#define DREAM_GPIO_H2W_SEL1 (DREAM_GPIO_MISC2_BASE + 7)
> +
> +#define DREAM_GPIO_SPOTLIGHT_EN (DREAM_GPIO_MISC3_BASE + 0)
> +#define DREAM_GPIO_FLASH_EN (DREAM_GPIO_MISC3_BASE + 1)
> +#define DREAM_GPIO_I2C_PULL (DREAM_GPIO_MISC3_BASE + 2)
> +#define DREAM_GPIO_TP_I2C_PULL (DREAM_GPIO_MISC3_BASE + 3)
> +#define DREAM_GPIO_TP_EN (DREAM_GPIO_MISC3_BASE + 4)
> +#define DREAM_GPIO_JOG_EN (DREAM_GPIO_MISC3_BASE + 5)
> +#define DREAM_GPIO_UI_LED_EN (DREAM_GPIO_MISC3_BASE + 6)
> +#define DREAM_GPIO_QTKEY_LED_EN (DREAM_GPIO_MISC3_BASE + 7)
> +
> +#define DREAM_GPIO_VCM_PWDN (DREAM_GPIO_MISC4_BASE + 0)
> +#define DREAM_GPIO_USB_H2W_SW (DREAM_GPIO_MISC4_BASE + 1)
> +#define DREAM_GPIO_COMPASS_RST_N (DREAM_GPIO_MISC4_BASE + 2)
> +#define DREAM_GPIO_HAPTIC_EN_UP (DREAM_GPIO_MISC4_BASE + 3)
> +#define DREAM_GPIO_HAPTIC_EN_MAIN (DREAM_GPIO_MISC4_BASE + 4)
> +#define DREAM_GPIO_USB_PHY_RST_N (DREAM_GPIO_MISC4_BASE + 5)
> +#define DREAM_GPIO_WIFI_PA_RESETX (DREAM_GPIO_MISC4_BASE + 6)
> +#define DREAM_GPIO_WIFI_EN (DREAM_GPIO_MISC4_BASE + 7)
> +
> +#define DREAM_GPIO_BT_32K_EN (DREAM_GPIO_MISC5_BASE + 0)
> +#define DREAM_GPIO_MAC_32K_EN (DREAM_GPIO_MISC5_BASE + 1)
> +#define DREAM_GPIO_MDDI_32K_EN (DREAM_GPIO_MISC5_BASE + 2)
> +#define DREAM_GPIO_COMPASS_32K_EN (DREAM_GPIO_MISC5_BASE + 3)
> +
> +#define DREAM_GPIO_NAVI_ACT_N (DREAM_GPIO_INT2_BASE + 0)
> +#define DREAM_GPIO_COMPASS_IRQ (DREAM_GPIO_INT2_BASE + 1)
> +#define DREAM_GPIO_SLIDING_DET (DREAM_GPIO_INT2_BASE + 2)
> +#define DREAM_GPIO_AUD_HSMIC_DET_N (DREAM_GPIO_INT2_BASE + 3)
> +#define DREAM_GPIO_SD_DOOR_N (DREAM_GPIO_INT2_BASE + 4)
> +#define DREAM_GPIO_CAM_BTN_STEP1_N (DREAM_GPIO_INT2_BASE + 5)
> +#define DREAM_GPIO_CAM_BTN_STEP2_N (DREAM_GPIO_INT2_BASE + 6)
> +#define DREAM_GPIO_TP_ATT_N (DREAM_GPIO_INT2_BASE + 7)
> +#define DREAM_GPIO_BANK0_FIRST_INT_SOURCE (DREAM_GPIO_NAVI_ACT_N)
> +#define DREAM_GPIO_BANK0_LAST_INT_SOURCE (DREAM_GPIO_TP_ATT_N)
> +
> +#define DREAM_GPIO_H2W_DAT_GPI (DREAM_GPIO_MISC1_BASE + 0)
> +#define DREAM_GPIO_H2W_CLK_GPI (DREAM_GPIO_MISC1_BASE + 1)
> +#define DREAM_GPIO_CPLD128_VER_0 (DREAM_GPIO_MISC1_BASE + 4)
> +#define DREAM_GPIO_CPLD128_VER_1 (DREAM_GPIO_MISC1_BASE + 5)
> +#define DREAM_GPIO_CPLD128_VER_2 (DREAM_GPIO_MISC1_BASE + 6)
> +#define DREAM_GPIO_CPLD128_VER_3 (DREAM_GPIO_MISC1_BASE + 7)
> +
> +#define DREAM_GPIO_SDMC_CD_N (DREAM_GPIO_VIRTUAL_BASE + 0)
> +#define DREAM_GPIO_END (DREAM_GPIO_SDMC_CD_N)
> +#define DREAM_GPIO_BANK1_FIRST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
> +#define DREAM_GPIO_BANK1_LAST_INT_SOURCE (DREAM_GPIO_SDMC_CD_N)
> +
> +#endif
>

--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2009-12-25 23:50:39

by Daniel Walker

[permalink] [raw]
Subject: Re: [patch] GPIO support for HTC Dream

On Fri, 2009-12-25 at 18:10 +0100, Pavel Machek wrote:
> Hi!
>
> Daniel, can we get it merged? It is perfect(TM) :-).

Yeah, but the one you originally sent was tab damaged .. So could you
resend it?

Daniel

2009-12-26 08:52:08

by Pavel Machek

[permalink] [raw]
Subject: Re: [patch] GPIO support for HTC Dream

On Fri 2009-12-25 15:49:10, Daniel Walker wrote:
> On Fri, 2009-12-25 at 18:10 +0100, Pavel Machek wrote:
> > Hi!
> >
> > Daniel, can we get it merged? It is perfect(TM) :-).
>
> Yeah, but the one you originally sent was tab damaged .. So could you
> resend it?

Ok, I'll resend it privately. Tell me if it arrives damaged. Aha, do
you mean real tab damage, or "spaces used instead of tabs in gpio.h"?
I see the second problem.
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html