From d1f5ab52773e90199ba413f44fce59c8ffe66621 Mon Sep 17 00:00:00 2001 From: Justin Patrin Date: Sun, 15 Apr 2007 05:13:40 +0000 Subject: linux-rp-2.6.20: update sharpsl-rc patch to allow corgi to compile --- packages/linux/linux-rp-2.6.20/defconfig-c7x0 | 2 +- packages/linux/linux-rp-2.6.20/sharpsl-rc-r0.patch | 491 ------------------- packages/linux/linux-rp-2.6.20/sharpsl-rc-r1.patch | 519 +++++++++++++++++++++ packages/linux/linux-rp_2.6.20.bb | 4 +- 4 files changed, 522 insertions(+), 494 deletions(-) delete mode 100644 packages/linux/linux-rp-2.6.20/sharpsl-rc-r0.patch create mode 100644 packages/linux/linux-rp-2.6.20/sharpsl-rc-r1.patch diff --git a/packages/linux/linux-rp-2.6.20/defconfig-c7x0 b/packages/linux/linux-rp-2.6.20/defconfig-c7x0 index 73d826ff24..ad7fca8861 100644 --- a/packages/linux/linux-rp-2.6.20/defconfig-c7x0 +++ b/packages/linux/linux-rp-2.6.20/defconfig-c7x0 @@ -1606,4 +1606,4 @@ CONFIG_CRC32=y CONFIG_LIBCRC32C=m CONFIG_ZLIB_INFLATE=y CONFIG_ZLIB_DEFLATE=y -CONFIG_SHARPSL_RC=n +CONFIG_SHARPSL_RC=m diff --git a/packages/linux/linux-rp-2.6.20/sharpsl-rc-r0.patch b/packages/linux/linux-rp-2.6.20/sharpsl-rc-r0.patch deleted file mode 100644 index 9761f43aca..0000000000 --- a/packages/linux/linux-rp-2.6.20/sharpsl-rc-r0.patch +++ /dev/null @@ -1,491 +0,0 @@ -Index: linux-2.6.20/arch/arm/mach-pxa/spitz.c -=================================================================== ---- linux-2.6.20.orig/arch/arm/mach-pxa/spitz.c -+++ linux-2.6.20/arch/arm/mach-pxa/spitz.c -@@ -244,6 +244,13 @@ static struct platform_device spitzkbd_d - .id = -1, - }; - -+/* -+ * Spitz Remote Control Device -+ */ -+static struct platform_device sharpsl_rc_device = { -+ .name = "sharpsl-remote-control", -+ .id = -1, -+}; - - /* - * Spitz LEDs -@@ -476,6 +483,7 @@ static struct platform_device *devices[] - &spitzscoop_device, - &spitzssp_device, - &spitzkbd_device, -+ &sharpsl_rc_device, - &spitzts_device, - &spitzbl_device, - &spitzled_device, -Index: linux-2.6.20/drivers/input/keyboard/Kconfig -=================================================================== ---- linux-2.6.20.orig/drivers/input/keyboard/Kconfig -+++ linux-2.6.20/drivers/input/keyboard/Kconfig -@@ -154,6 +154,17 @@ config KEYBOARD_SPITZ - To compile this driver as a module, choose M here: the - module will be called spitzkbd. - -+config SHARPSL_RC -+ tristate "Sharp SL-Cxx00 Remote Control" -+ depends on PXA_SHARPSL -+ default y -+ help -+ Say Y here to enable the remote on the Sharp Zaurus SL-Cxx00, -+ SL-C1000, SL-C3000 and Sl-C3100 series of PDAs. -+ -+ To compile this driver as a module, choose M here: the -+ module will be called sharpsl_rc. -+ - config KEYBOARD_AMIGA - tristate "Amiga keyboard" - depends on AMIGA -Index: linux-2.6.20/drivers/input/keyboard/Makefile -=================================================================== ---- linux-2.6.20.orig/drivers/input/keyboard/Makefile -+++ linux-2.6.20/drivers/input/keyboard/Makefile -@@ -14,6 +14,7 @@ obj-$(CONFIG_KEYBOARD_NEWTON) += newton - obj-$(CONFIG_KEYBOARD_STOWAWAY) += stowaway.o - obj-$(CONFIG_KEYBOARD_CORGI) += corgikbd.o - obj-$(CONFIG_KEYBOARD_SPITZ) += spitzkbd.o -+obj-$(CONFIG_SHARPSL_RC) += sharpsl_rc.o - obj-$(CONFIG_KEYBOARD_HIL) += hil_kbd.o - obj-$(CONFIG_KEYBOARD_HIL_OLD) += hilkbd.o - obj-$(CONFIG_KEYBOARD_OMAP) += omap-keypad.o -Index: linux-2.6.20/drivers/input/keyboard/sharpsl_rc.c -=================================================================== ---- /dev/null -+++ linux-2.6.20/drivers/input/keyboard/sharpsl_rc.c -@@ -0,0 +1,263 @@ -+/* -+ * Keyboard driver for Sharp Clamshell Models (SL-Cxx00) -+ * -+ * Copyright (c) 2004-2005 Richard Purdie -+ * -+ * Based on corgikbd.c and Sharp's RC driver -+ * -+ * This program is free software; you can redistribute it and/or modify -+ * it under the terms of the GNU General Public License version 2 as -+ * published by the Free Software Foundation. -+ * -+ */ -+ -+#define DEBUG 1 -+#include -+#include -+#include -+#include -+#include -+#include -+#include -+#include -+ -+#include -+#include -+#include -+#include -+#include -+#include -+ -+#define DPRINTK(fmt, args...) dev_dbg(data->dev, fmt "\n", ##args) -+ -+struct remote_control_key { -+ unsigned char min; -+ unsigned char max; -+ unsigned char key; -+}; -+ -+static struct remote_control_key spitz_remote_keys[] = { -+ { 25, 35, KEY_STOPCD}, -+ { 55, 65, KEY_PLAYPAUSE}, -+ { 85, 95, KEY_NEXTSONG}, -+ { 115, 125, KEY_VOLUMEUP}, -+ { 145, 155, KEY_PREVIOUSSONG}, -+ { 180, 190, KEY_MUTE}, -+ { 215, 225, KEY_VOLUMEDOWN}, -+}; -+ -+#define RELEASE_HI 230 -+#define MAX_EARPHONE 6 -+#define RC_POLL_MS 10 -+#define RC_FINISH_MS 500 -+#define WAIT_STATE 3 -+#define NOISE_THRESHOLD 100 -+ -+struct sharpsl_rc { -+ struct input_dev *input; -+ struct device *dev; -+ -+ spinlock_t lock; -+ struct timer_list rctimer; -+ struct timer_list rctimer_finish; -+ -+ unsigned int handling_press; -+ unsigned int noise; -+ unsigned int state; -+ unsigned int last_key; -+}; -+ -+static int get_remocon_raw(void) -+{ -+ int i, val; -+ -+ val = sharpsl_pm_pxa_read_max1111(MAX1111_REMCOM); -+ for (i = 0; i < ARRAY_SIZE(spitz_remote_keys); ++i) { -+ if (val >= spitz_remote_keys[i].min -+ && val <= spitz_remote_keys[i].max) { -+ printk("get_remocon_raw: VAL=%i, KEY=%i\n", val, spitz_remote_keys[i].key); -+ return spitz_remote_keys[i].key; -+ } -+ } -+ return 0; -+} -+ -+static irqreturn_t sharpsl_rc_interrupt(int irq, void *dev_id, struct pt_regs *regs) -+{ -+ struct sharpsl_rc *data = dev_id; -+ DPRINTK("sharpsl_rc_interrupt %d\n", irq); -+ if (!data->handling_press) { -+ DPRINTK("handling interrupt"); -+ data->handling_press = 1; -+ data->noise = 0; -+ data->state = 0; -+ data->last_key = 0; -+ -+ reset_scoop_gpio(&spitzscoop2_device.dev, SPITZ_SCP2_AKIN_PULLUP); -+ -+ mod_timer(&data->rctimer, jiffies + msecs_to_jiffies(RC_POLL_MS)); -+ } -+ return IRQ_HANDLED; -+} -+ -+static void sharpsl_rc_timer_callback(unsigned long dataPtr) -+{ -+ struct sharpsl_rc *data = (struct sharpsl_rc *) dataPtr; -+ int timer = 1; -+ int key = get_remocon_raw(); -+ DPRINTK("timer callback, key: %d", key); -+ -+ //wait for value to stabilize -+ if (data->state < WAIT_STATE) { -+ if (data->last_key != key) { -+ ++data->noise; -+ if (data->noise > NOISE_THRESHOLD) { -+ DPRINTK("too much noise, bailing"); -+ timer = 0; -+ } -+ data->state = 0; -+ } else { -+ ++data->state; -+ } -+ data->last_key = key; -+ -+ //stable value, send event -+ } else if (data->state == WAIT_STATE) { -+ data->noise = 0; -+ //non-key returned, skip the rest of the states and bail now -+ if (data->last_key == 0) { -+ DPRINTK("non-key detected %d, noise: %d", data->last_key, data->noise); -+ timer = 0; -+ //send button press -+ } else { -+ DPRINTK("key press detected %d, noise %d", data->last_key, data->noise); -+ input_report_key(data->input, data->last_key, 1); -+ } -+ ++data->state; -+ -+ //wait until key is released -+ } else if (data->state < WAIT_STATE * 2) { -+ if (key == data->last_key -+ && data->noise < NOISE_THRESHOLD) { -+ data->state = WAIT_STATE + 1; -+ ++data->noise; -+ } else { -+ ++data->state; -+ } -+ //key is released, send event -+ } else { -+ //send button release -+ DPRINTK("release key %d", data->last_key); -+ input_report_key(data->input, data->last_key, 0); -+ timer = 0; -+ } -+ if (timer) { -+ mod_timer(&data->rctimer, jiffies + msecs_to_jiffies(RC_POLL_MS)); -+ } else { -+ set_scoop_gpio(&spitzscoop2_device.dev, SPITZ_SCP2_AKIN_PULLUP); -+ data->handling_press = 0; -+ } -+} -+ -+static int __init sharpsl_rc_probe(struct platform_device *pdev) -+{ -+ struct sharpsl_rc *sharpsl_rc; -+ struct input_dev *input_dev; -+ int i, ret; -+ -+ dev_dbg(&pdev->dev, "sharpsl_rc_probe\n"); -+ -+ sharpsl_rc = kzalloc(sizeof(struct sharpsl_rc), GFP_KERNEL); -+ input_dev = input_allocate_device(); -+ if (!sharpsl_rc || !input_dev) { -+ kfree(sharpsl_rc); -+ input_free_device(input_dev); -+ return -ENOMEM; -+ } -+ -+ platform_set_drvdata(pdev, sharpsl_rc); -+ -+ sharpsl_rc->dev = &pdev->dev; -+ sharpsl_rc->input = input_dev; -+ spin_lock_init(&sharpsl_rc->lock); -+ -+ /* Init Remote Control Timer */ -+ init_timer(&sharpsl_rc->rctimer); -+ sharpsl_rc->rctimer.function = sharpsl_rc_timer_callback; -+ sharpsl_rc->rctimer.data = (unsigned long) sharpsl_rc; -+ -+ input_dev->name = "Spitz Remote Control"; -+ input_dev->phys = "sharpsl_rc/input0"; -+ input_dev->id.bustype = BUS_HOST; -+ input_dev->id.vendor = 0x0001; -+ input_dev->id.product = 0x0001; -+ input_dev->id.version = 0x0100; -+ input_dev->cdev.dev = &pdev->dev; -+ input_dev->private = sharpsl_rc; -+ -+ input_dev->evbit[0] = BIT(EV_KEY); -+ -+ for (i = 0; i <= ARRAY_SIZE(spitz_remote_keys); i++) -+ set_bit(spitz_remote_keys[i].key, input_dev->keybit); -+ -+ input_register_device(sharpsl_rc->input); -+ -+ pxa_gpio_mode(SPITZ_GPIO_AK_INT | GPIO_IN); -+ ret = request_irq(SPITZ_IRQ_GPIO_AK_INT, -+ sharpsl_rc_interrupt, -+ IRQF_DISABLED | IRQF_TRIGGER_RISING | IRQF_SHARED, -+ "sharpsl_rc", -+ sharpsl_rc); -+ if (ret < 0) { -+ dev_dbg(&pdev->dev, "Can't get IRQ: %d!\n", i); -+ kfree(sharpsl_rc); -+ input_free_device(input_dev); -+ return ret; -+ } -+ -+ return 0; -+} -+ -+static int sharpsl_rc_remove(struct platform_device *pdev) -+{ -+ struct sharpsl_rc *sharpsl_rc = platform_get_drvdata(pdev); -+ -+ dev_dbg(&pdev->dev, "sharpsl_rc_remove\n"); -+ -+ free_irq(SPITZ_IRQ_GPIO_AK_INT, sharpsl_rc); -+ del_timer_sync(&sharpsl_rc->rctimer); -+ input_unregister_device(sharpsl_rc->input); -+ kfree(sharpsl_rc); -+ -+ return 0; -+} -+ -+static struct platform_driver sharpsl_rc_driver = { -+ .probe = sharpsl_rc_probe, -+ .remove = sharpsl_rc_remove, -+ .suspend = NULL, -+ .resume = NULL, -+ .driver = { -+ .name = "sharpsl-remote-control", -+ }, -+}; -+ -+static int __devinit sharpsl_rc_init(void) -+{ -+ printk("sharpsl_rc_init\n"); -+ return platform_driver_register(&sharpsl_rc_driver); -+} -+ -+static void __exit sharpsl_rc_exit(void) -+{ -+ printk("sharpsl_rc_exit\n"); -+ platform_driver_unregister(&sharpsl_rc_driver); -+} -+ -+module_init(sharpsl_rc_init); -+module_exit(sharpsl_rc_exit); -+ -+MODULE_AUTHOR("Justin Patrin "); -+MODULE_AUTHOR("Richard Purdie "); -+MODULE_DESCRIPTION("SharpSL Remote Control Driver"); -+MODULE_LICENSE("GPL"); -Index: linux-2.6.20/drivers/input/keyboard/spitzkbd.c -=================================================================== ---- linux-2.6.20.orig/drivers/input/keyboard/spitzkbd.c -+++ linux-2.6.20/drivers/input/keyboard/spitzkbd.c -@@ -19,6 +19,7 @@ - #include - #include - #include -+#include - - #include - #include -@@ -279,13 +280,21 @@ static irqreturn_t spitzkbd_hinge_isr(in - static int sharpsl_hinge_state; - static int hinge_count; - -+void spitzkbd_handle_sharpsl_rc(void *arg) { -+ request_module("sharpsl_rc"); -+} -+ -+DECLARE_WORK(spitzkbd_work, spitzkbd_handle_sharpsl_rc); -+ - static void spitzkbd_hinge_timer(unsigned long data) - { - struct spitzkbd *spitzkbd_data = (struct spitzkbd *) data; - unsigned long state; - unsigned long flags; -+ unsigned int headphone, remote; - - state = GPLR(SPITZ_GPIO_SWA) & (GPIO_bit(SPITZ_GPIO_SWA)|GPIO_bit(SPITZ_GPIO_SWB)); -+ state |= (GPLR(SPITZ_GPIO_HP_IN) & GPIO_bit(SPITZ_GPIO_HP_IN)); - state |= (GPLR(SPITZ_GPIO_AK_INT) & GPIO_bit(SPITZ_GPIO_AK_INT)); - if (state != sharpsl_hinge_state) { - hinge_count = 0; -@@ -299,9 +308,18 @@ static void spitzkbd_hinge_timer(unsigne - - input_report_switch(spitzkbd_data->input, SW_LID, ((GPLR(SPITZ_GPIO_SWA) & GPIO_bit(SPITZ_GPIO_SWA)) != 0)); - input_report_switch(spitzkbd_data->input, SW_TABLET_MODE, ((GPLR(SPITZ_GPIO_SWB) & GPIO_bit(SPITZ_GPIO_SWB)) != 0)); -- input_report_switch(spitzkbd_data->input, SW_HEADPHONE_INSERT, ((GPLR(SPITZ_GPIO_AK_INT) & GPIO_bit(SPITZ_GPIO_AK_INT)) != 0)); -+ -+ headphone = ((GPLR(SPITZ_GPIO_HP_IN) & GPIO_bit(SPITZ_GPIO_HP_IN)) != 0); -+ input_report_switch(spitzkbd_data->input, SW_HEADPHONE_INSERT, headphone); -+ -+ remote = headphone && ((GPLR(SPITZ_GPIO_AK_INT) & GPIO_bit(SPITZ_GPIO_AK_INT)) == 0); -+ input_report_switch(spitzkbd_data->input, SW_REMOTE_INSERT, remote); - input_sync(spitzkbd_data->input); - -+ if (remote) { -+ schedule_work(&spitzkbd_work); -+ } -+ - spin_unlock_irqrestore(&spitzkbd_data->lock, flags); - } else { - mod_timer(&spitzkbd_data->htimer, jiffies + msecs_to_jiffies(HINGE_SCAN_INTERVAL)); -@@ -394,6 +412,7 @@ static int __init spitzkbd_probe(struct - set_bit(SW_LID, input_dev->swbit); - set_bit(SW_TABLET_MODE, input_dev->swbit); - set_bit(SW_HEADPHONE_INSERT, input_dev->swbit); -+ set_bit(SW_REMOTE_INSERT, input_dev->swbit); - - err = input_register_device(input_dev); - if (err) -@@ -431,9 +450,12 @@ static int __init spitzkbd_probe(struct - request_irq(SPITZ_IRQ_GPIO_SWB, spitzkbd_hinge_isr, - IRQF_DISABLED | IRQF_TRIGGER_RISING | IRQF_TRIGGER_FALLING, - "Spitzkbd SWB", spitzkbd); -- request_irq(SPITZ_IRQ_GPIO_AK_INT, spitzkbd_hinge_isr, -+ request_irq(SPITZ_IRQ_GPIO_HP_IN, spitzkbd_hinge_isr, - IRQF_DISABLED | IRQF_TRIGGER_RISING | IRQF_TRIGGER_FALLING, - "Spitzkbd HP", spitzkbd); -+ request_irq(SPITZ_IRQ_GPIO_AK_INT, spitzkbd_hinge_isr, -+ IRQF_DISABLED | IRQF_TRIGGER_RISING | IRQF_TRIGGER_FALLING | IRQF_SHARED, -+ "Spitzkbd HP Type", spitzkbd); - - return 0; - -@@ -454,6 +476,7 @@ static int spitzkbd_remove(struct platfo - free_irq(SPITZ_IRQ_GPIO_ON_KEY, spitzkbd); - free_irq(SPITZ_IRQ_GPIO_SWA, spitzkbd); - free_irq(SPITZ_IRQ_GPIO_SWB, spitzkbd); -+ free_irq(SPITZ_IRQ_GPIO_HP_IN, spitzkbd); - free_irq(SPITZ_IRQ_GPIO_AK_INT, spitzkbd); - - del_timer_sync(&spitzkbd->htimer); -Index: linux-2.6.20/arch/arm/mach-pxa/sharpsl.h -=================================================================== ---- linux-2.6.20.orig/arch/arm/mach-pxa/sharpsl.h -+++ linux-2.6.20/arch/arm/mach-pxa/sharpsl.h -@@ -50,15 +50,10 @@ void spitz_wait_hsync(void); - - #define READ_GPIO_BIT(x) (GPLR(x) & GPIO_bit(x)) - --/* MAX1111 Channel Definitions */ --#define MAX1111_BATT_VOLT 4u --#define MAX1111_BATT_TEMP 2u --#define MAX1111_ACIN_VOLT 6u -- - extern struct battery_thresh spitz_battery_levels_acin[]; - extern struct battery_thresh spitz_battery_levels_noac[]; - void sharpsl_pm_pxa_init(void); - void sharpsl_pm_pxa_remove(void); --int sharpsl_pm_pxa_read_max1111(int channel); -+ - - -Index: linux-2.6.20/arch/arm/mach-pxa/sharpsl_pm.c -=================================================================== ---- linux-2.6.20.orig/arch/arm/mach-pxa/sharpsl_pm.c -+++ linux-2.6.20/arch/arm/mach-pxa/sharpsl_pm.c -@@ -135,6 +135,8 @@ int sharpsl_pm_pxa_read_max1111(int chan - | MAXCTRL_SGL | MAXCTRL_UNI | MAXCTRL_STR); - } - -+EXPORT_SYMBOL(sharpsl_pm_pxa_read_max1111); -+ - void sharpsl_pm_pxa_init(void) - { - pxa_gpio_mode(sharpsl_pm.machinfo->gpio_acin | GPIO_IN); -Index: linux-2.6.20/include/asm-arm/hardware/sharpsl_pm.h -=================================================================== ---- linux-2.6.20.orig/include/asm-arm/hardware/sharpsl_pm.h -+++ linux-2.6.20/include/asm-arm/hardware/sharpsl_pm.h -@@ -104,3 +104,10 @@ irqreturn_t sharpsl_ac_isr(int irq, void - irqreturn_t sharpsl_chrg_full_isr(int irq, void *dev_id); - irqreturn_t sharpsl_fatal_isr(int irq, void *dev_id); - -+/* MAX1111 Channel Definitions */ -+#define MAX1111_REMCOM 0u -+#define MAX1111_BATT_VOLT 4u -+#define MAX1111_BATT_TEMP 2u -+#define MAX1111_ACIN_VOLT 6u -+ -+int sharpsl_pm_pxa_read_max1111(int channel); -Index: linux-2.6.20/include/linux/input.h -=================================================================== ---- linux-2.6.20.orig/include/linux/input.h -+++ linux-2.6.20/include/linux/input.h -@@ -602,6 +602,7 @@ struct input_absinfo { - #define SW_LID 0x00 /* set = lid shut */ - #define SW_TABLET_MODE 0x01 /* set = tablet mode */ - #define SW_HEADPHONE_INSERT 0x02 /* set = inserted */ -+#define SW_REMOTE_INSERT 0x04 /* set = remote */ - #define SW_MAX 0x0f - - /* -Index: linux-2.6.20/arch/arm/mach-pxa/spitz_pm.c -=================================================================== ---- linux-2.6.20.orig/arch/arm/mach-pxa/spitz_pm.c -+++ linux-2.6.20/arch/arm/mach-pxa/spitz_pm.c -@@ -161,6 +161,13 @@ static int spitz_should_wakeup(unsigned - if (resume_on_alarm && (PEDR & PWER_RTC)) - is_resume |= PWER_RTC; - -+ printk("wakeup: PEDR: %x, PKSR: %x, HP_IN: %x, AK_INT: %x\n", PEDR, PKSR, GPIO_bit(SPITZ_GPIO_HP_IN), GPIO_bit(SPITZ_GPIO_AK_INT)); -+ -+ //remote/headphone interrupt, wakeup -+ if (PEDR == 0 && (PKSR & 0xc0d01) != 0) { -+ is_resume |= PWER_RTC; -+ } -+ - dev_dbg(sharpsl_pm.dev, "is_resume: %x\n",is_resume); - return is_resume; - } diff --git a/packages/linux/linux-rp-2.6.20/sharpsl-rc-r1.patch b/packages/linux/linux-rp-2.6.20/sharpsl-rc-r1.patch new file mode 100644 index 0000000000..8230d53392 --- /dev/null +++ b/packages/linux/linux-rp-2.6.20/sharpsl-rc-r1.patch @@ -0,0 +1,519 @@ +Index: linux-2.6.20/arch/arm/mach-pxa/spitz.c +=================================================================== +--- linux-2.6.20.orig/arch/arm/mach-pxa/spitz.c ++++ linux-2.6.20/arch/arm/mach-pxa/spitz.c +@@ -244,6 +244,13 @@ static struct platform_device spitzkbd_d + .id = -1, + }; + ++/* ++ * Spitz Remote Control Device ++ */ ++static struct platform_device sharpsl_rc_device = { ++ .name = "sharpsl-remote-control", ++ .id = -1, ++}; + + /* + * Spitz LEDs +@@ -476,6 +483,7 @@ static struct platform_device *devices[] + &spitzscoop_device, + &spitzssp_device, + &spitzkbd_device, ++ &sharpsl_rc_device, + &spitzts_device, + &spitzbl_device, + &spitzled_device, +Index: linux-2.6.20/drivers/input/keyboard/Kconfig +=================================================================== +--- linux-2.6.20.orig/drivers/input/keyboard/Kconfig ++++ linux-2.6.20/drivers/input/keyboard/Kconfig +@@ -154,6 +154,17 @@ config KEYBOARD_SPITZ + To compile this driver as a module, choose M here: the + module will be called spitzkbd. + ++config SHARPSL_RC ++ tristate "Sharp SL-Cxx00 Remote Control" ++ depends on PXA_SHARPSL ++ default y ++ help ++ Say Y here to enable the remote on the Sharp Zaurus SL-Cxx00, ++ SL-C1000, SL-C3000 and Sl-C3100 series of PDAs. ++ ++ To compile this driver as a module, choose M here: the ++ module will be called sharpsl_rc. ++ + config KEYBOARD_AMIGA + tristate "Amiga keyboard" + depends on AMIGA +Index: linux-2.6.20/drivers/input/keyboard/Makefile +=================================================================== +--- linux-2.6.20.orig/drivers/input/keyboard/Makefile ++++ linux-2.6.20/drivers/input/keyboard/Makefile +@@ -14,6 +14,7 @@ obj-$(CONFIG_KEYBOARD_NEWTON) += newton + obj-$(CONFIG_KEYBOARD_STOWAWAY) += stowaway.o + obj-$(CONFIG_KEYBOARD_CORGI) += corgikbd.o + obj-$(CONFIG_KEYBOARD_SPITZ) += spitzkbd.o ++obj-$(CONFIG_SHARPSL_RC) += sharpsl_rc.o + obj-$(CONFIG_KEYBOARD_HIL) += hil_kbd.o + obj-$(CONFIG_KEYBOARD_HIL_OLD) += hilkbd.o + obj-$(CONFIG_KEYBOARD_OMAP) += omap-keypad.o +Index: linux-2.6.20/drivers/input/keyboard/sharpsl_rc.c +=================================================================== +--- /dev/null ++++ linux-2.6.20/drivers/input/keyboard/sharpsl_rc.c +@@ -0,0 +1,291 @@ ++/* ++ * Keyboard driver for Sharp Clamshell Models (SL-Cxx00) ++ * ++ * Copyright (c) 2004-2005 Richard Purdie ++ * ++ * Based on corgikbd.c and Sharp's RC driver ++ * ++ * This program is free software; you can redistribute it and/or modify ++ * it under the terms of the GNU General Public License version 2 as ++ * published by the Free Software Foundation. ++ * ++ */ ++ ++#define DEBUG 1 ++#include ++#include ++#include ++#include ++#include ++#include ++#include ++#include ++ ++#ifdef CONFIG_MACH_SPITZ ++#include ++#endif ++#ifdef CONFIG_MACH_CORGI ++#include ++#endif ++ ++#include ++#include ++#include ++#include ++#include ++ ++#define DPRINTK(fmt, args...) dev_dbg(data->dev, fmt "\n", ##args) ++ ++struct remote_control_key { ++ unsigned char min; ++ unsigned char max; ++ unsigned char key; ++}; ++ ++#ifdef CONFIG_MACH_SPITZ ++#define REMOTE_AKIN_PULLUP SPITZ_SCP2_AKIN_PULLUP ++#define REMOTE_SCOOP_DEVICE spitzscoop2_device ++#define REMOTE_GPIO_INT SPITZ_GPIO_AK_INT ++#define REMOTE_IRQ_INT SPITZ_IRQ_GPIO_AK_INT ++static struct remote_control_key remote_keys[] = { ++ { 25, 35, KEY_STOPCD}, ++ { 55, 65, KEY_PLAYPAUSE}, ++ { 85, 95, KEY_NEXTSONG}, ++ { 115, 125, KEY_VOLUMEUP}, ++ { 145, 155, KEY_PREVIOUSSONG}, ++ { 180, 190, KEY_MUTE}, ++ { 215, 225, KEY_VOLUMEDOWN}, ++}; ++#endif ++#ifdef CONFIG_MACH_CORGI ++#define REMOTE_AKIN_PULLUP CORGI_SCP_AKIN_PULLUP ++#define REMOTE_SCOOP_DEVICE corgiscoop_device ++#define REMOTE_GPIO_INT CORGI_GPIO_AK_INT ++#define REMOTE_IRQ_INT CORGI_IRQ_GPIO_AK_INT ++static struct remote_control_key remote_keys[] = { ++ //These need to be fixed for the CE-RH1's values ++ { 25, 35, KEY_STOPCD}, ++ { 55, 65, KEY_PLAYPAUSE}, ++ { 85, 95, KEY_NEXTSONG}, ++ { 115, 125, KEY_VOLUMEUP}, ++ { 145, 155, KEY_PREVIOUSSONG}, ++ { 180, 190, KEY_MUTE}, ++ { 215, 225, KEY_VOLUMEDOWN}, ++}; ++#endif ++ ++#define RELEASE_HI 230 ++#define MAX_EARPHONE 6 ++#define RC_POLL_MS 10 ++#define RC_FINISH_MS 500 ++#define WAIT_STATE 3 ++#define NOISE_THRESHOLD 100 ++ ++struct sharpsl_rc { ++ struct input_dev *input; ++ struct device *dev; ++ ++ spinlock_t lock; ++ struct timer_list rctimer; ++ struct timer_list rctimer_finish; ++ ++ unsigned int handling_press; ++ unsigned int noise; ++ unsigned int state; ++ unsigned int last_key; ++}; ++ ++static int get_remocon_raw(void) ++{ ++ int i, val; ++ ++ val = sharpsl_pm_pxa_read_max1111(MAX1111_REMCOM); ++ for (i = 0; i < ARRAY_SIZE(remote_keys); ++i) { ++ if (val >= remote_keys[i].min ++ && val <= remote_keys[i].max) { ++ printk("get_remocon_raw: VAL=%i, KEY=%i\n", val, remote_keys[i].key); ++ return remote_keys[i].key; ++ } ++ } ++ return 0; ++} ++ ++static irqreturn_t sharpsl_rc_interrupt(int irq, void *dev_id, struct pt_regs *regs) ++{ ++ struct sharpsl_rc *data = dev_id; ++ DPRINTK("sharpsl_rc_interrupt %d\n", irq); ++ if (!data->handling_press) { ++ DPRINTK("handling interrupt"); ++ data->handling_press = 1; ++ data->noise = 0; ++ data->state = 0; ++ data->last_key = 0; ++ ++ reset_scoop_gpio(&REMOTE_SCOOP_DEVICE.dev, REMOTE_AKIN_PULLUP); ++ ++ mod_timer(&data->rctimer, jiffies + msecs_to_jiffies(RC_POLL_MS)); ++ } ++ return IRQ_HANDLED; ++} ++ ++static void sharpsl_rc_timer_callback(unsigned long dataPtr) ++{ ++ struct sharpsl_rc *data = (struct sharpsl_rc *) dataPtr; ++ int timer = 1; ++ int key = get_remocon_raw(); ++ DPRINTK("timer callback, key: %d", key); ++ ++ //wait for value to stabilize ++ if (data->state < WAIT_STATE) { ++ if (data->last_key != key) { ++ ++data->noise; ++ if (data->noise > NOISE_THRESHOLD) { ++ DPRINTK("too much noise, bailing"); ++ timer = 0; ++ } ++ data->state = 0; ++ } else { ++ ++data->state; ++ } ++ data->last_key = key; ++ ++ //stable value, send event ++ } else if (data->state == WAIT_STATE) { ++ data->noise = 0; ++ //non-key returned, skip the rest of the states and bail now ++ if (data->last_key == 0) { ++ DPRINTK("non-key detected %d, noise: %d", data->last_key, data->noise); ++ timer = 0; ++ //send button press ++ } else { ++ DPRINTK("key press detected %d, noise %d", data->last_key, data->noise); ++ input_report_key(data->input, data->last_key, 1); ++ } ++ ++data->state; ++ ++ //wait until key is released ++ } else if (data->state < WAIT_STATE * 2) { ++ if (key == data->last_key ++ && data->noise < NOISE_THRESHOLD) { ++ data->state = WAIT_STATE + 1; ++ ++data->noise; ++ } else { ++ ++data->state; ++ } ++ //key is released, send event ++ } else { ++ //send button release ++ DPRINTK("release key %d", data->last_key); ++ input_report_key(data->input, data->last_key, 0); ++ timer = 0; ++ } ++ if (timer) { ++ mod_timer(&data->rctimer, jiffies + msecs_to_jiffies(RC_POLL_MS)); ++ } else { ++ set_scoop_gpio(&REMOTE_SCOOP_DEVICE.dev, REMOTE_AKIN_PULLUP); ++ data->handling_press = 0; ++ } ++} ++ ++static int __init sharpsl_rc_probe(struct platform_device *pdev) ++{ ++ struct sharpsl_rc *sharpsl_rc; ++ struct input_dev *input_dev; ++ int i, ret; ++ ++ dev_dbg(&pdev->dev, "sharpsl_rc_probe\n"); ++ ++ sharpsl_rc = kzalloc(sizeof(struct sharpsl_rc), GFP_KERNEL); ++ input_dev = input_allocate_device(); ++ if (!sharpsl_rc || !input_dev) { ++ kfree(sharpsl_rc); ++ input_free_device(input_dev); ++ return -ENOMEM; ++ } ++ ++ platform_set_drvdata(pdev, sharpsl_rc); ++ ++ sharpsl_rc->dev = &pdev->dev; ++ sharpsl_rc->input = input_dev; ++ spin_lock_init(&sharpsl_rc->lock); ++ ++ /* Init Remote Control Timer */ ++ init_timer(&sharpsl_rc->rctimer); ++ sharpsl_rc->rctimer.function = sharpsl_rc_timer_callback; ++ sharpsl_rc->rctimer.data = (unsigned long) sharpsl_rc; ++ ++ input_dev->name = "Sharp Remote Control CE-RHX"; ++ input_dev->phys = "sharpsl_rc/input0"; ++ input_dev->id.bustype = BUS_HOST; ++ input_dev->id.vendor = 0x0001; ++ input_dev->id.product = 0x0001; ++ input_dev->id.version = 0x0100; ++ input_dev->cdev.dev = &pdev->dev; ++ input_dev->private = sharpsl_rc; ++ ++ input_dev->evbit[0] = BIT(EV_KEY); ++ ++ for (i = 0; i <= ARRAY_SIZE(remote_keys); i++) ++ set_bit(remote_keys[i].key, input_dev->keybit); ++ ++ input_register_device(sharpsl_rc->input); ++ ++ pxa_gpio_mode(REMOTE_GPIO_INT | GPIO_IN); ++ ret = request_irq(REMOTE_IRQ_INT, ++ sharpsl_rc_interrupt, ++ IRQF_DISABLED | IRQF_TRIGGER_RISING | IRQF_SHARED, ++ "sharpsl_rc", ++ sharpsl_rc); ++ if (ret < 0) { ++ dev_dbg(&pdev->dev, "Can't get IRQ: %d!\n", i); ++ kfree(sharpsl_rc); ++ input_free_device(input_dev); ++ return ret; ++ } ++ ++ return 0; ++} ++ ++static int sharpsl_rc_remove(struct platform_device *pdev) ++{ ++ struct sharpsl_rc *sharpsl_rc = platform_get_drvdata(pdev); ++ ++ dev_dbg(&pdev->dev, "sharpsl_rc_remove\n"); ++ ++ free_irq(REMOTE_IRQ_INT, sharpsl_rc); ++ del_timer_sync(&sharpsl_rc->rctimer); ++ input_unregister_device(sharpsl_rc->input); ++ kfree(sharpsl_rc); ++ ++ return 0; ++} ++ ++static struct platform_driver sharpsl_rc_driver = { ++ .probe = sharpsl_rc_probe, ++ .remove = sharpsl_rc_remove, ++ .suspend = NULL, ++ .resume = NULL, ++ .driver = { ++ .name = "sharpsl-remote-control", ++ }, ++}; ++ ++static int __devinit sharpsl_rc_init(void) ++{ ++ printk("sharpsl_rc_init\n"); ++ return platform_driver_register(&sharpsl_rc_driver); ++} ++ ++static void __exit sharpsl_rc_exit(void) ++{ ++ printk("sharpsl_rc_exit\n"); ++ platform_driver_unregister(&sharpsl_rc_driver); ++} ++ ++module_init(sharpsl_rc_init); ++module_exit(sharpsl_rc_exit); ++ ++MODULE_AUTHOR("Justin Patrin "); ++MODULE_AUTHOR("Richard Purdie "); ++MODULE_DESCRIPTION("SharpSL Remote Control Driver"); ++MODULE_LICENSE("GPL"); +Index: linux-2.6.20/drivers/input/keyboard/spitzkbd.c +=================================================================== +--- linux-2.6.20.orig/drivers/input/keyboard/spitzkbd.c ++++ linux-2.6.20/drivers/input/keyboard/spitzkbd.c +@@ -19,6 +19,7 @@ + #include + #include + #include ++#include + + #include + #include +@@ -279,13 +280,21 @@ static irqreturn_t spitzkbd_hinge_isr(in + static int sharpsl_hinge_state; + static int hinge_count; + ++void spitzkbd_handle_sharpsl_rc(void *arg) { ++ request_module("sharpsl_rc"); ++} ++ ++DECLARE_WORK(spitzkbd_work, spitzkbd_handle_sharpsl_rc); ++ + static void spitzkbd_hinge_timer(unsigned long data) + { + struct spitzkbd *spitzkbd_data = (struct spitzkbd *) data; + unsigned long state; + unsigned long flags; ++ unsigned int headphone, remote; + + state = GPLR(SPITZ_GPIO_SWA) & (GPIO_bit(SPITZ_GPIO_SWA)|GPIO_bit(SPITZ_GPIO_SWB)); ++ state |= (GPLR(SPITZ_GPIO_HP_IN) & GPIO_bit(SPITZ_GPIO_HP_IN)); + state |= (GPLR(SPITZ_GPIO_AK_INT) & GPIO_bit(SPITZ_GPIO_AK_INT)); + if (state != sharpsl_hinge_state) { + hinge_count = 0; +@@ -299,9 +308,18 @@ static void spitzkbd_hinge_timer(unsigne + + input_report_switch(spitzkbd_data->input, SW_LID, ((GPLR(SPITZ_GPIO_SWA) & GPIO_bit(SPITZ_GPIO_SWA)) != 0)); + input_report_switch(spitzkbd_data->input, SW_TABLET_MODE, ((GPLR(SPITZ_GPIO_SWB) & GPIO_bit(SPITZ_GPIO_SWB)) != 0)); +- input_report_switch(spitzkbd_data->input, SW_HEADPHONE_INSERT, ((GPLR(SPITZ_GPIO_AK_INT) & GPIO_bit(SPITZ_GPIO_AK_INT)) != 0)); ++ ++ headphone = ((GPLR(SPITZ_GPIO_HP_IN) & GPIO_bit(SPITZ_GPIO_HP_IN)) != 0); ++ input_report_switch(spitzkbd_data->input, SW_HEADPHONE_INSERT, headphone); ++ ++ remote = headphone && ((GPLR(SPITZ_GPIO_AK_INT) & GPIO_bit(SPITZ_GPIO_AK_INT)) == 0); ++ input_report_switch(spitzkbd_data->input, SW_REMOTE_INSERT, remote); + input_sync(spitzkbd_data->input); + ++ if (remote) { ++ schedule_work(&spitzkbd_work); ++ } ++ + spin_unlock_irqrestore(&spitzkbd_data->lock, flags); + } else { + mod_timer(&spitzkbd_data->htimer, jiffies + msecs_to_jiffies(HINGE_SCAN_INTERVAL)); +@@ -394,6 +412,7 @@ static int __init spitzkbd_probe(struct + set_bit(SW_LID, input_dev->swbit); + set_bit(SW_TABLET_MODE, input_dev->swbit); + set_bit(SW_HEADPHONE_INSERT, input_dev->swbit); ++ set_bit(SW_REMOTE_INSERT, input_dev->swbit); + + err = input_register_device(input_dev); + if (err) +@@ -431,9 +450,12 @@ static int __init spitzkbd_probe(struct + request_irq(SPITZ_IRQ_GPIO_SWB, spitzkbd_hinge_isr, + IRQF_DISABLED | IRQF_TRIGGER_RISING | IRQF_TRIGGER_FALLING, + "Spitzkbd SWB", spitzkbd); +- request_irq(SPITZ_IRQ_GPIO_AK_INT, spitzkbd_hinge_isr, ++ request_irq(SPITZ_IRQ_GPIO_HP_IN, spitzkbd_hinge_isr, + IRQF_DISABLED | IRQF_TRIGGER_RISING | IRQF_TRIGGER_FALLING, + "Spitzkbd HP", spitzkbd); ++ request_irq(SPITZ_IRQ_GPIO_AK_INT, spitzkbd_hinge_isr, ++ IRQF_DISABLED | IRQF_TRIGGER_RISING | IRQF_TRIGGER_FALLING | IRQF_SHARED, ++ "Spitzkbd HP Type", spitzkbd); + + return 0; + +@@ -454,6 +476,7 @@ static int spitzkbd_remove(struct platfo + free_irq(SPITZ_IRQ_GPIO_ON_KEY, spitzkbd); + free_irq(SPITZ_IRQ_GPIO_SWA, spitzkbd); + free_irq(SPITZ_IRQ_GPIO_SWB, spitzkbd); ++ free_irq(SPITZ_IRQ_GPIO_HP_IN, spitzkbd); + free_irq(SPITZ_IRQ_GPIO_AK_INT, spitzkbd); + + del_timer_sync(&spitzkbd->htimer); +Index: linux-2.6.20/arch/arm/mach-pxa/sharpsl.h +=================================================================== +--- linux-2.6.20.orig/arch/arm/mach-pxa/sharpsl.h ++++ linux-2.6.20/arch/arm/mach-pxa/sharpsl.h +@@ -50,15 +50,10 @@ void spitz_wait_hsync(void); + + #define READ_GPIO_BIT(x) (GPLR(x) & GPIO_bit(x)) + +-/* MAX1111 Channel Definitions */ +-#define MAX1111_BATT_VOLT 4u +-#define MAX1111_BATT_TEMP 2u +-#define MAX1111_ACIN_VOLT 6u +- + extern struct battery_thresh spitz_battery_levels_acin[]; + extern struct battery_thresh spitz_battery_levels_noac[]; + void sharpsl_pm_pxa_init(void); + void sharpsl_pm_pxa_remove(void); +-int sharpsl_pm_pxa_read_max1111(int channel); ++ + + +Index: linux-2.6.20/arch/arm/mach-pxa/sharpsl_pm.c +=================================================================== +--- linux-2.6.20.orig/arch/arm/mach-pxa/sharpsl_pm.c ++++ linux-2.6.20/arch/arm/mach-pxa/sharpsl_pm.c +@@ -135,6 +135,8 @@ int sharpsl_pm_pxa_read_max1111(int chan + | MAXCTRL_SGL | MAXCTRL_UNI | MAXCTRL_STR); + } + ++EXPORT_SYMBOL(sharpsl_pm_pxa_read_max1111); ++ + void sharpsl_pm_pxa_init(void) + { + pxa_gpio_mode(sharpsl_pm.machinfo->gpio_acin | GPIO_IN); +Index: linux-2.6.20/include/asm-arm/hardware/sharpsl_pm.h +=================================================================== +--- linux-2.6.20.orig/include/asm-arm/hardware/sharpsl_pm.h ++++ linux-2.6.20/include/asm-arm/hardware/sharpsl_pm.h +@@ -104,3 +104,10 @@ irqreturn_t sharpsl_ac_isr(int irq, void + irqreturn_t sharpsl_chrg_full_isr(int irq, void *dev_id); + irqreturn_t sharpsl_fatal_isr(int irq, void *dev_id); + ++/* MAX1111 Channel Definitions */ ++#define MAX1111_REMCOM 0u ++#define MAX1111_BATT_VOLT 4u ++#define MAX1111_BATT_TEMP 2u ++#define MAX1111_ACIN_VOLT 6u ++ ++int sharpsl_pm_pxa_read_max1111(int channel); +Index: linux-2.6.20/include/linux/input.h +=================================================================== +--- linux-2.6.20.orig/include/linux/input.h ++++ linux-2.6.20/include/linux/input.h +@@ -602,6 +602,7 @@ struct input_absinfo { + #define SW_LID 0x00 /* set = lid shut */ + #define SW_TABLET_MODE 0x01 /* set = tablet mode */ + #define SW_HEADPHONE_INSERT 0x02 /* set = inserted */ ++#define SW_REMOTE_INSERT 0x04 /* set = remote */ + #define SW_MAX 0x0f + + /* +Index: linux-2.6.20/arch/arm/mach-pxa/spitz_pm.c +=================================================================== +--- linux-2.6.20.orig/arch/arm/mach-pxa/spitz_pm.c ++++ linux-2.6.20/arch/arm/mach-pxa/spitz_pm.c +@@ -161,6 +161,13 @@ static int spitz_should_wakeup(unsigned + if (resume_on_alarm && (PEDR & PWER_RTC)) + is_resume |= PWER_RTC; + ++ printk("wakeup: PEDR: %x, PKSR: %x, HP_IN: %x, AK_INT: %x\n", PEDR, PKSR, GPIO_bit(SPITZ_GPIO_HP_IN), GPIO_bit(SPITZ_GPIO_AK_INT)); ++ ++ //remote/headphone interrupt, wakeup ++ if (PEDR == 0 && (PKSR & 0xc0d01) != 0) { ++ is_resume |= PWER_RTC; ++ } ++ + dev_dbg(sharpsl_pm.dev, "is_resume: %x\n",is_resume); + return is_resume; + } diff --git a/packages/linux/linux-rp_2.6.20.bb b/packages/linux/linux-rp_2.6.20.bb index d645a0e771..23cf54e794 100644 --- a/packages/linux/linux-rp_2.6.20.bb +++ b/packages/linux/linux-rp_2.6.20.bb @@ -1,6 +1,6 @@ require linux-rp.inc -PR = "r12" +PR = "r13" # Handy URLs # git://git.kernel.org/pub/scm/linux/kernel/git/torvalds/linux-2.6.git;protocol=git;tag=ef7d1b244fa6c94fb76d5f787b8629df64ea4046 @@ -54,7 +54,7 @@ SRC_URI = "http://www.kernel.org/pub/linux/kernel/v2.6/linux-2.6.20.tar.bz2 \ file://connectplus-remove-ide-HACK.patch;patch=1;status=hack \ file://squashfs3.0-2.6.15.patch;patch=1;status=external \ file://vesafb-tng-1.0-rc2-2.6.20-rc2.patch;patch=1;status=external \ - file://sharpsl-rc-r0.patch;patch=1 \ + file://sharpsl-rc-r1.patch;patch=1 \ file://defconfig-c7x0 \ file://defconfig-hx2000 \ file://defconfig-collie \ -- cgit v1.2.3