linux-arm-kernel.lists.infradead.org archive mirror
 help / color / mirror / Atom feed
* [PATCH 0/3] at91: Add support for Snapper 9260/9G20 modules
@ 2010-06-16 21:20 Ryan Mallon
  2010-06-16 21:20 ` [PATCH 1/3] AT91: Define NR_BUILTIN_GPIO Ryan Mallon
                   ` (2 more replies)
  0 siblings, 3 replies; 11+ messages in thread
From: Ryan Mallon @ 2010-06-16 21:20 UTC (permalink / raw)
  To: linux-arm-kernel

Add support for Bluewater Systems Snapper 9260/9G20 modules. 

In order to fully support the modules, NR_BUILTIN_GPIO must be defined
for at91 and vbus polarity and polling have been added to the at91 udc
driver.

Ryan Mallon (3):
  AT91: Define NR_BUILTIN_GPIO
  at91_udc: Add vbus polarity and polling mode
  at91: Add support for Bluewater Systems Snapper 9260/9G20 modules

 arch/arm/mach-at91/Kconfig              |   11 ++
 arch/arm/mach-at91/Makefile             |    3 +
 arch/arm/mach-at91/board-snapper9260.c  |  189 +++++++++++++++++++++++++++++++
 arch/arm/mach-at91/include/mach/board.h |    2 +
 arch/arm/mach-at91/include/mach/gpio.h  |    1 +
 drivers/usb/gadget/at91_udc.c           |   45 ++++++--
 drivers/usb/gadget/at91_udc.h           |    1 +
 7 files changed, 242 insertions(+), 10 deletions(-)
 create mode 100644 arch/arm/mach-at91/board-snapper9260.c

^ permalink raw reply	[flat|nested] 11+ messages in thread

* [PATCH 1/3] AT91: Define NR_BUILTIN_GPIO
  2010-06-16 21:20 [PATCH 0/3] at91: Add support for Snapper 9260/9G20 modules Ryan Mallon
@ 2010-06-16 21:20 ` Ryan Mallon
  2010-06-16 21:20 ` [PATCH 2/3] at91_udc: Add vbus polarity and polling mode Ryan Mallon
  2010-06-16 21:20 ` [PATCH 3/3] at91: Add support for Bluewater Systems Snapper 9260/9G20 modules Ryan Mallon
  2 siblings, 0 replies; 11+ messages in thread
From: Ryan Mallon @ 2010-06-16 21:20 UTC (permalink / raw)
  To: linux-arm-kernel

Add definition for NR_BUILTIN_GPIO for AT91 family

Signed-off-by: Ryan Mallon <ryan@bluewatersys.com>
---
 arch/arm/mach-at91/include/mach/gpio.h |    1 +
 1 files changed, 1 insertions(+), 0 deletions(-)

diff --git a/arch/arm/mach-at91/include/mach/gpio.h b/arch/arm/mach-at91/include/mach/gpio.h
index 04c91e3..bfdd8ab 100644
--- a/arch/arm/mach-at91/include/mach/gpio.h
+++ b/arch/arm/mach-at91/include/mach/gpio.h
@@ -19,6 +19,7 @@
 #define PIN_BASE		NR_AIC_IRQS
 
 #define MAX_GPIO_BANKS		5
+#define NR_BUILTIN_GPIO		(PIN_BASE + (MAX_GPIO_BANKS * 32))
 
 /* these pin numbers double as IRQ numbers, like AT91xxx_ID_* values */
 
-- 
1.5.5.1

^ permalink raw reply related	[flat|nested] 11+ messages in thread

* [PATCH 2/3] at91_udc: Add vbus polarity and polling mode
  2010-06-16 21:20 [PATCH 0/3] at91: Add support for Snapper 9260/9G20 modules Ryan Mallon
  2010-06-16 21:20 ` [PATCH 1/3] AT91: Define NR_BUILTIN_GPIO Ryan Mallon
@ 2010-06-16 21:20 ` Ryan Mallon
  2010-06-17 22:03   ` Ryan Mallon
  2010-06-16 21:20 ` [PATCH 3/3] at91: Add support for Bluewater Systems Snapper 9260/9G20 modules Ryan Mallon
  2 siblings, 1 reply; 11+ messages in thread
From: Ryan Mallon @ 2010-06-16 21:20 UTC (permalink / raw)
  To: linux-arm-kernel

Allow the vbus signal to optionally use polling. This is required if
the vbus signal is connected to an non-interrupting io expander for
example. Also add an option to have vbus be an active low signal. Both
options are set in the platform data for the device.

Signed-off-by: Ryan Mallon <ryan@bluewatersys.com>
---
 arch/arm/mach-at91/include/mach/board.h |    2 +
 drivers/usb/gadget/at91_udc.c           |   45 ++++++++++++++++++++++++-------
 drivers/usb/gadget/at91_udc.h           |    1 +
 3 files changed, 38 insertions(+), 10 deletions(-)

diff --git a/arch/arm/mach-at91/include/mach/board.h b/arch/arm/mach-at91/include/mach/board.h
index df2ed84..58528aa 100644
--- a/arch/arm/mach-at91/include/mach/board.h
+++ b/arch/arm/mach-at91/include/mach/board.h
@@ -44,6 +44,8 @@
  /* USB Device */
 struct at91_udc_data {
 	u8	vbus_pin;		/* high == host powering us */
+	u8	vbus_active_low;	/* vbus polarity */
+	u8	vbus_polled;		/* Use polling, not interrupt */
 	u8	pullup_pin;		/* active == D+ pulled up */
 	u8	pullup_active_low;	/* true == pullup_pin is active low */
 };
diff --git a/drivers/usb/gadget/at91_udc.c b/drivers/usb/gadget/at91_udc.c
index eaa79c8..9649d76 100644
--- a/drivers/usb/gadget/at91_udc.c
+++ b/drivers/usb/gadget/at91_udc.c
@@ -76,6 +76,7 @@
 static const char driver_name [] = "at91_udc";
 static const char ep0name[] = "ep0";
 
+#define VBUS_POLL_TIMEOUT	msecs_to_jiffies(1000)
 
 #define at91_udp_read(dev, reg) \
 	__raw_readl((dev)->udp_baseaddr + (reg))
@@ -1556,20 +1557,37 @@ static struct at91_udc controller = {
 	/* ep6 and ep7 are also reserved (custom silicon might use them) */
 };
 
+static void at91_vbus_update(struct at91_udc *udc)
+{
+	unsigned value;
+
+	value = gpio_get_value(udc->board.vbus_pin);
+	if (udc->board.vbus_active_low)
+		value ^= 1;
+	if (value != udc->vbus)
+		at91_vbus_session(&udc->gadget, value);
+}
+
 static irqreturn_t at91_vbus_irq(int irq, void *_udc)
 {
 	struct at91_udc	*udc = _udc;
-	unsigned	value;
 
 	/* vbus needs at least brief debouncing */
 	udelay(10);
-	value = gpio_get_value(udc->board.vbus_pin);
-	if (value != udc->vbus)
-		at91_vbus_session(&udc->gadget, value);
+	at91_vbus_update(udc);
 
 	return IRQ_HANDLED;
 }
 
+static void at91_vbus_timer(unsigned long data)
+{
+	struct at91_udc *udc = (struct at91_udc *)data;
+
+	at91_vbus_update(udc);
+	if (!timer_pending(&udc->vbus_timer))
+	    mod_timer(&udc->vbus_timer, jiffies + VBUS_POLL_TIMEOUT);
+}
+
 int usb_gadget_register_driver (struct usb_gadget_driver *driver)
 {
 	struct at91_udc	*udc = &controller;
@@ -1764,12 +1782,19 @@ static int __init at91udc_probe(struct platform_device *pdev)
 		 * a pending interrupt.
 		 */
 		udc->vbus = gpio_get_value(udc->board.vbus_pin);
-		if (request_irq(udc->board.vbus_pin, at91_vbus_irq,
-				IRQF_DISABLED, driver_name, udc)) {
-			DBG("request vbus irq %d failed\n",
-					udc->board.vbus_pin);
-			retval = -EBUSY;
-			goto fail3;
+		if (udc->board.vbus_polled) {
+			setup_timer(&udc->vbus_timer, at91_vbus_timer,
+				    (unsigned long)udc);
+			mod_timer(&udc->vbus_timer,
+				  jiffies + VBUS_POLL_TIMEOUT);
+		} else {
+			if (request_irq(udc->board.vbus_pin, at91_vbus_irq,
+					IRQF_DISABLED, driver_name, udc)) {
+				DBG("request vbus irq %d failed\n",
+				    udc->board.vbus_pin);
+				retval = -EBUSY;
+				goto fail3;
+			}
 		}
 	} else {
 		DBG("no VBUS detection, assuming always-on\n");
diff --git a/drivers/usb/gadget/at91_udc.h b/drivers/usb/gadget/at91_udc.h
index c65d622..2ebd665 100644
--- a/drivers/usb/gadget/at91_udc.h
+++ b/drivers/usb/gadget/at91_udc.h
@@ -144,6 +144,7 @@ struct at91_udc {
 	struct proc_dir_entry		*pde;
 	void __iomem			*udp_baseaddr;
 	int				udp_irq;
+	struct timer_list		vbus_timer;
 };
 
 static inline struct at91_udc *to_udc(struct usb_gadget *g)
-- 
1.5.5.1

^ permalink raw reply related	[flat|nested] 11+ messages in thread

* [PATCH 3/3] at91: Add support for Bluewater Systems Snapper 9260/9G20 modules
  2010-06-16 21:20 [PATCH 0/3] at91: Add support for Snapper 9260/9G20 modules Ryan Mallon
  2010-06-16 21:20 ` [PATCH 1/3] AT91: Define NR_BUILTIN_GPIO Ryan Mallon
  2010-06-16 21:20 ` [PATCH 2/3] at91_udc: Add vbus polarity and polling mode Ryan Mallon
@ 2010-06-16 21:20 ` Ryan Mallon
  2 siblings, 0 replies; 11+ messages in thread
From: Ryan Mallon @ 2010-06-16 21:20 UTC (permalink / raw)
  To: linux-arm-kernel

Add support for Bluewater Systems Snapper 9260/9G20 modules

Signed-off-by: Ryan Mallon <ryan@bluewatersys.com>
---
 arch/arm/mach-at91/Kconfig             |   11 ++
 arch/arm/mach-at91/Makefile            |    3 +
 arch/arm/mach-at91/board-snapper9260.c |  189 ++++++++++++++++++++++++++++++++
 3 files changed, 203 insertions(+), 0 deletions(-)
 create mode 100644 arch/arm/mach-at91/board-snapper9260.c

diff --git a/arch/arm/mach-at91/Kconfig b/arch/arm/mach-at91/Kconfig
index 841eaf8..939bccd 100644
--- a/arch/arm/mach-at91/Kconfig
+++ b/arch/arm/mach-at91/Kconfig
@@ -366,6 +366,17 @@ config MACH_STAMP9G20
 
 endif
 
+if (ARCH_AT91SAM9260 || ARCH_AT91SAM9G20)
+comment "AT91SAM9260/AT91SAM9G20 boards"
+
+config MACH_SNAPPER_9260
+        bool "Bluewater Systems Snapper 9260/9G20 module"
+        help
+          Select this if you are using the Bluewater Systems Snapper 9260 or
+          Snapper 9G20 modules.
+          <http://www.bluewatersys.com/>
+endif
+
 # ----------------------------------------------------------
 
 if ARCH_AT91SAM9G45
diff --git a/arch/arm/mach-at91/Makefile b/arch/arm/mach-at91/Makefile
index c1f821e..ca2ac00 100644
--- a/arch/arm/mach-at91/Makefile
+++ b/arch/arm/mach-at91/Makefile
@@ -66,6 +66,9 @@ obj-$(CONFIG_MACH_CPU9G20)	+= board-cpu9krea.o
 obj-$(CONFIG_MACH_STAMP9G20)	+= board-stamp9g20.o
 obj-$(CONFIG_MACH_PORTUXG20)	+= board-stamp9g20.o
 
+# AT91SAM9260/AT91SAM9G20 board-specific support
+obj-$(CONFIG_MACH_SNAPPER_9260)	+= board-snapper9260.o
+
 # AT91SAM9G45 board-specific support
 obj-$(CONFIG_MACH_AT91SAM9G45EKES) += board-sam9m10g45ek.o
 
diff --git a/arch/arm/mach-at91/board-snapper9260.c b/arch/arm/mach-at91/board-snapper9260.c
new file mode 100644
index 0000000..91ed809
--- /dev/null
+++ b/arch/arm/mach-at91/board-snapper9260.c
@@ -0,0 +1,189 @@
+/*
+ * linux/arch/arm/mach-at91/board-snapper9260.c
+ *
+ *  Copyright (C) 2010 Bluewater System Ltd
+ *
+ * Author: Andre Renaud <andre@bluewatersys.com>
+ * Author: Ryan Mallon  <ryan@bluewatersys.com>
+ *
+ * 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.
+ *
+ * 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.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
+ *
+ */
+
+#include <linux/init.h>
+#include <linux/gpio.h>
+#include <linux/platform_device.h>
+#include <linux/spi/spi.h>
+#include <linux/i2c/pca953x.h>
+
+#include <asm/mach-types.h>
+#include <asm/mach/arch.h>
+
+#include <mach/hardware.h>
+#include <mach/board.h>
+#include <mach/at91sam9_smc.h>
+
+#include "sam9_smc.h"
+#include "generic.h"
+
+#define SNAPPER9260_IO_EXP_GPIO(x)	(NR_BUILTIN_GPIO + (x))
+
+static void __init snapper9260_map_io(void)
+{
+	at91sam9260_initialize(18432000);
+
+	/* Debug on ttyS0 */
+	at91_register_uart(0, 0, 0);
+	at91_set_serial_console(0);
+
+	at91_register_uart(AT91SAM9260_ID_US0, 1, 
+			   ATMEL_UART_CTS | ATMEL_UART_RTS);
+	at91_register_uart(AT91SAM9260_ID_US1, 2,
+			   ATMEL_UART_CTS | ATMEL_UART_RTS);	
+	at91_register_uart(AT91SAM9260_ID_US2, 3, 0);	
+}
+
+static void __init snapper9260_init_irq(void)
+{
+	at91sam9260_init_interrupts(NULL);
+}
+
+static struct at91_usbh_data __initdata snapper9260_usbh_data = {
+	.ports		= 2,
+};
+
+static struct at91_udc_data __initdata snapper9260_udc_data = {
+	.vbus_pin		= SNAPPER9260_IO_EXP_GPIO(5),
+	.vbus_active_low	= 1,
+	.vbus_polled		= 1,
+};
+
+static struct at91_eth_data snapper9260_macb_data = {
+	.is_rmii	= 1,
+};
+
+static struct mtd_partition __initdata snapper9260_nand_partitions[] = {
+	{
+		.name	= "Preboot",
+		.offset	= 0,
+		.size	= SZ_128K,
+	},
+	{
+		.name	= "Bootloader",
+		.offset	= MTDPART_OFS_APPEND,
+		.size	= SZ_256K,
+	},
+	{
+		.name	= "Environment",
+		.offset	= MTDPART_OFS_APPEND,
+		.size	= SZ_128K,
+	},
+	{
+		.name	= "Kernel",
+		.offset	= MTDPART_OFS_APPEND,
+		.size	= SZ_4M,
+	},
+	{
+		.name	= "Filesystem",
+		.offset	= MTDPART_OFS_APPEND,
+		.size	= MTDPART_SIZ_FULL,
+	},
+};
+
+static struct mtd_partition * __init 
+snapper9260_nand_partition_info(int size, int *num_partitions)
+{
+	*num_partitions = ARRAY_SIZE(snapper9260_nand_partitions);
+	return snapper9260_nand_partitions;
+}
+
+static struct atmel_nand_data __initdata snapper9260_nand_data = {
+	.ale		= 21,
+	.cle		= 22,
+	.rdy_pin	= AT91_PIN_PC13,
+	.partition_info	= snapper9260_nand_partition_info,
+	.bus_width_16	= 0,
+};
+
+static struct sam9_smc_config __initdata snapper9260_nand_smc_config = {
+	.ncs_read_setup		= 0,
+	.nrd_setup		= 0,
+	.ncs_write_setup	= 0,
+	.nwe_setup		= 0,
+
+	.ncs_read_pulse		= 5,
+	.nrd_pulse		= 2,
+	.ncs_write_pulse	= 5,
+	.nwe_pulse		= 2,
+	
+	.read_cycle		= 7,
+	.write_cycle		= 7,
+
+	.mode			= (AT91_SMC_READMODE | AT91_SMC_WRITEMODE |
+				   AT91_SMC_EXNWMODE_DISABLE),
+	.tdf_cycles		= 1,
+};
+
+static struct pca953x_platform_data snapper9260_io_expander_data = {
+	.gpio_base		= SNAPPER9260_IO_EXP_GPIO(0),
+};
+
+static struct i2c_board_info __initdata snapper9260_i2c_devices[] = {
+	{
+		/* IO expander */
+		I2C_BOARD_INFO("max7312", 0x28),
+		.platform_data = &snapper9260_io_expander_data,
+	},
+	{
+		/* Audio codec */
+		I2C_BOARD_INFO("tlv320aic23", 0x1a),
+	},
+	{
+		/* RTC */
+		I2C_BOARD_INFO("isl1208", 0x6f),
+	},
+};
+
+static void __init snapper9260_add_device_nand(void)
+{
+	at91_set_A_periph(AT91_PIN_PC14, 0);
+	sam9_smc_configure(3, &snapper9260_nand_smc_config);
+	at91_add_device_nand(&snapper9260_nand_data);
+}
+
+static void __init snapper9260_board_init(void)
+{
+	at91_add_device_i2c(snapper9260_i2c_devices,
+			    ARRAY_SIZE(snapper9260_i2c_devices));
+	at91_add_device_serial();
+	at91_add_device_usbh(&snapper9260_usbh_data);
+	at91_add_device_udc(&snapper9260_udc_data);
+	at91_add_device_eth(&snapper9260_macb_data);
+	at91_add_device_ssc(AT91SAM9260_ID_SSC, (ATMEL_SSC_TF | ATMEL_SSC_TK |
+						 ATMEL_SSC_TD | ATMEL_SSC_RD));
+	snapper9260_add_device_nand();
+}
+
+MACHINE_START(SNAPPER_9260, "Bluewater Systems Snapper 9260/9G20 module")
+	.phys_io	= AT91_BASE_SYS,
+	.io_pg_offst	= (AT91_VA_BASE_SYS >> 18) & 0xfffc,
+	.boot_params	= AT91_SDRAM_BASE + 0x100,
+	.timer		= &at91sam926x_timer,
+	.map_io		= snapper9260_map_io,
+	.init_irq	= snapper9260_init_irq,
+	.init_machine	= snapper9260_board_init,
+MACHINE_END
+
+
-- 
1.5.5.1

^ permalink raw reply related	[flat|nested] 11+ messages in thread

* [PATCH 2/3] at91_udc: Add vbus polarity and polling mode
  2010-06-16 21:20 ` [PATCH 2/3] at91_udc: Add vbus polarity and polling mode Ryan Mallon
@ 2010-06-17 22:03   ` Ryan Mallon
  0 siblings, 0 replies; 11+ messages in thread
From: Ryan Mallon @ 2010-06-17 22:03 UTC (permalink / raw)
  To: linux-arm-kernel

I realised this patch was not quite correct. If vbus is on an io
expander then the gpio can potentially sleep, so use the gpiolib
cansleep variants when in polling mode. Also, do not try and
enable/disable wakeups on vbus if it is polled.

---
at91_udc: Add vbus polarity and polling mode

Allow the vbus signal to optionally use polling. This is required if the
vbus signal is connected to an non-interrupting io expander for example.
If vbus is in polling mode, then it is assumed that the vbus gpio may
sleep. Also add an option to have vbus be an active low signal. Both
options are set in the platform data for the device.

Signed-off-by: Ryan Mallon <ryan@bluewatersys.com>
---

diff --git a/arch/arm/mach-at91/include/mach/board.h b/arch/arm/mach-at91/include/mach/board.h
index df2ed84..58528aa 100644
--- a/arch/arm/mach-at91/include/mach/board.h
+++ b/arch/arm/mach-at91/include/mach/board.h
@@ -44,6 +44,8 @@
  /* USB Device */
 struct at91_udc_data {
 	u8	vbus_pin;		/* high == host powering us */
+	u8	vbus_active_low;	/* vbus polarity */
+	u8	vbus_polled;		/* Use polling, not interrupt */
 	u8	pullup_pin;		/* active == D+ pulled up */
 	u8	pullup_active_low;	/* true == pullup_pin is active low */
 };
diff --git a/drivers/usb/gadget/at91_udc.c b/drivers/usb/gadget/at91_udc.c
index eaa79c8..469a64c 100644
--- a/drivers/usb/gadget/at91_udc.c
+++ b/drivers/usb/gadget/at91_udc.c
@@ -76,6 +76,7 @@
 static const char driver_name [] = "at91_udc";
 static const char ep0name[] = "ep0";
 
+#define VBUS_POLL_TIMEOUT	msecs_to_jiffies(1000)
 
 #define at91_udp_read(dev, reg) \
 	__raw_readl((dev)->udp_baseaddr + (reg))
@@ -1556,20 +1557,49 @@ static struct at91_udc controller = {
 	/* ep6 and ep7 are also reserved (custom silicon might use them) */
 };
 
+static void at91_vbus_update(struct at91_udc *udc, unsigned value)
+{
+	if (udc->board.vbus_active_low)
+		value ^= 1;
+	if (value != udc->vbus)
+		at91_vbus_session(&udc->gadget, value);
+}
+
 static irqreturn_t at91_vbus_irq(int irq, void *_udc)
 {
 	struct at91_udc	*udc = _udc;
-	unsigned	value;
 
 	/* vbus needs at least brief debouncing */
 	udelay(10);
-	value = gpio_get_value(udc->board.vbus_pin);
-	if (value != udc->vbus)
-		at91_vbus_session(&udc->gadget, value);
+	at91_vbus_update(udc, gpio_get_value(udc->board.vbus_pin));
 
 	return IRQ_HANDLED;
 }
 
+static void at91_vbus_timer_work(struct work_struct *work)
+{
+	struct at91_udc *udc = container_of(work, struct at91_udc, 
+					    vbus_timer_work);
+
+	at91_vbus_update(udc, gpio_get_value_cansleep(udc->board.vbus_pin));
+
+	if (!timer_pending(&udc->vbus_timer))
+		mod_timer(&udc->vbus_timer, jiffies + VBUS_POLL_TIMEOUT);
+}
+
+static void at91_vbus_timer(unsigned long data)
+{
+	struct at91_udc *udc = (struct at91_udc *)data;
+
+	/*
+	 * If we are polling vbus it is likely that the gpio is on an
+	 * bus such as i2c or spi which may sleep, so schedule some work
+	 * to read the vbus gpio
+	 */
+	if (!work_pending(&udc->vbus_timer_work))
+		schedule_work(&udc->vbus_timer_work);
+}
+
 int usb_gadget_register_driver (struct usb_gadget_driver *driver)
 {
 	struct at91_udc	*udc = &controller;
@@ -1763,13 +1793,22 @@ static int __init at91udc_probe(struct platform_device *pdev)
 		 * Get the initial state of VBUS - we cannot expect
 		 * a pending interrupt.
 		 */
-		udc->vbus = gpio_get_value(udc->board.vbus_pin);
-		if (request_irq(udc->board.vbus_pin, at91_vbus_irq,
-				IRQF_DISABLED, driver_name, udc)) {
-			DBG("request vbus irq %d failed\n",
-					udc->board.vbus_pin);
-			retval = -EBUSY;
-			goto fail3;
+		if (udc->board.vbus_polled) {
+			udc->vbus = gpio_get_value_cansleep(udc->board.vbus_pin);
+			INIT_WORK(&udc->vbus_timer_work, at91_vbus_timer_work);
+			setup_timer(&udc->vbus_timer, at91_vbus_timer,
+				    (unsigned long)udc);		
+			mod_timer(&udc->vbus_timer,
+				  jiffies + VBUS_POLL_TIMEOUT);
+		} else {
+			udc->vbus = gpio_get_value(udc->board.vbus_pin);
+			if (request_irq(udc->board.vbus_pin, at91_vbus_irq,
+					IRQF_DISABLED, driver_name, udc)) {
+				DBG("request vbus irq %d failed\n",
+				    udc->board.vbus_pin);
+				retval = -EBUSY;
+				goto fail3;
+			}
 		}
 	} else {
 		DBG("no VBUS detection, assuming always-on\n");
@@ -1855,7 +1894,7 @@ static int at91udc_suspend(struct platform_device *pdev, pm_message_t mesg)
 		enable_irq_wake(udc->udp_irq);
 
 	udc->active_suspend = wake;
-	if (udc->board.vbus_pin > 0 && wake)
+	if (udc->board.vbus_pin > 0 && !udc->board.vbus_polled && wake)
 		enable_irq_wake(udc->board.vbus_pin);
 	return 0;
 }
@@ -1864,7 +1903,8 @@ static int at91udc_resume(struct platform_device *pdev)
 {
 	struct at91_udc *udc = platform_get_drvdata(pdev);
 
-	if (udc->board.vbus_pin > 0 && udc->active_suspend)
+	if (udc->board.vbus_pin > 0 && !udc->board.vbus_polled && 
+	    udc->active_suspend)
 		disable_irq_wake(udc->board.vbus_pin);
 
 	/* maybe reconnect to host; if so, clocks on */
diff --git a/drivers/usb/gadget/at91_udc.h b/drivers/usb/gadget/at91_udc.h
index c65d622..a1f4f54 100644
--- a/drivers/usb/gadget/at91_udc.h
+++ b/drivers/usb/gadget/at91_udc.h
@@ -144,6 +144,8 @@ struct at91_udc {
 	struct proc_dir_entry		*pde;
 	void __iomem			*udp_baseaddr;
 	int				udp_irq;
+	struct timer_list		vbus_timer;
+	struct work_struct		vbus_timer_work;
 };
 
 static inline struct at91_udc *to_udc(struct usb_gadget *g)

^ permalink raw reply related	[flat|nested] 11+ messages in thread

* [PATCH 2/3] at91_udc: Add vbus polarity and polling mode
  2010-06-28  4:39 [PATCH 0/3] " Ryan Mallon
@ 2010-06-28  4:39 ` Ryan Mallon
  2010-06-30 21:02   ` Ryan Mallon
  2010-07-01 13:45   ` Nicolas Ferre
  0 siblings, 2 replies; 11+ messages in thread
From: Ryan Mallon @ 2010-06-28  4:39 UTC (permalink / raw)
  To: linux-arm-kernel

Allow the vbus signal to optionally use polling. This is required if
the vbus signal is connected to an non-interrupting io expander for
example. If vbus is in polling mode, then it is assumed that the vbus
gpio may sleep. Also add an option to have vbus be an active low
signal. Both options are set in the platform data for the device.

Signed-off-by: Ryan Mallon <ryan@bluewatersys.com>
---
 arch/arm/mach-at91/include/mach/board.h |    2 +
 drivers/usb/gadget/at91_udc.c           |   66 +++++++++++++++++++++++++------
 drivers/usb/gadget/at91_udc.h           |    2 +
 3 files changed, 57 insertions(+), 13 deletions(-)

diff --git a/arch/arm/mach-at91/include/mach/board.h b/arch/arm/mach-at91/include/mach/board.h
index df2ed84..58528aa 100644
--- a/arch/arm/mach-at91/include/mach/board.h
+++ b/arch/arm/mach-at91/include/mach/board.h
@@ -44,6 +44,8 @@
  /* USB Device */
 struct at91_udc_data {
 	u8	vbus_pin;		/* high == host powering us */
+	u8	vbus_active_low;	/* vbus polarity */
+	u8	vbus_polled;		/* Use polling, not interrupt */
 	u8	pullup_pin;		/* active == D+ pulled up */
 	u8	pullup_active_low;	/* true == pullup_pin is active low */
 };
diff --git a/drivers/usb/gadget/at91_udc.c b/drivers/usb/gadget/at91_udc.c
index eaa79c8..469a64c 100644
--- a/drivers/usb/gadget/at91_udc.c
+++ b/drivers/usb/gadget/at91_udc.c
@@ -76,6 +76,7 @@
 static const char driver_name [] = "at91_udc";
 static const char ep0name[] = "ep0";
 
+#define VBUS_POLL_TIMEOUT	msecs_to_jiffies(1000)
 
 #define at91_udp_read(dev, reg) \
 	__raw_readl((dev)->udp_baseaddr + (reg))
@@ -1556,20 +1557,49 @@ static struct at91_udc controller = {
 	/* ep6 and ep7 are also reserved (custom silicon might use them) */
 };
 
+static void at91_vbus_update(struct at91_udc *udc, unsigned value)
+{
+	if (udc->board.vbus_active_low)
+		value ^= 1;
+	if (value != udc->vbus)
+		at91_vbus_session(&udc->gadget, value);
+}
+
 static irqreturn_t at91_vbus_irq(int irq, void *_udc)
 {
 	struct at91_udc	*udc = _udc;
-	unsigned	value;
 
 	/* vbus needs at least brief debouncing */
 	udelay(10);
-	value = gpio_get_value(udc->board.vbus_pin);
-	if (value != udc->vbus)
-		at91_vbus_session(&udc->gadget, value);
+	at91_vbus_update(udc, gpio_get_value(udc->board.vbus_pin));
 
 	return IRQ_HANDLED;
 }
 
+static void at91_vbus_timer_work(struct work_struct *work)
+{
+	struct at91_udc *udc = container_of(work, struct at91_udc, 
+					    vbus_timer_work);
+
+	at91_vbus_update(udc, gpio_get_value_cansleep(udc->board.vbus_pin));
+
+	if (!timer_pending(&udc->vbus_timer))
+		mod_timer(&udc->vbus_timer, jiffies + VBUS_POLL_TIMEOUT);
+}
+
+static void at91_vbus_timer(unsigned long data)
+{
+	struct at91_udc *udc = (struct at91_udc *)data;
+
+	/*
+	 * If we are polling vbus it is likely that the gpio is on an
+	 * bus such as i2c or spi which may sleep, so schedule some work
+	 * to read the vbus gpio
+	 */
+	if (!work_pending(&udc->vbus_timer_work))
+		schedule_work(&udc->vbus_timer_work);
+}
+
 int usb_gadget_register_driver (struct usb_gadget_driver *driver)
 {
 	struct at91_udc	*udc = &controller;
@@ -1763,13 +1793,22 @@ static int __init at91udc_probe(struct platform_device *pdev)
 		 * Get the initial state of VBUS - we cannot expect
 		 * a pending interrupt.
 		 */
-		udc->vbus = gpio_get_value(udc->board.vbus_pin);
-		if (request_irq(udc->board.vbus_pin, at91_vbus_irq,
-				IRQF_DISABLED, driver_name, udc)) {
-			DBG("request vbus irq %d failed\n",
-					udc->board.vbus_pin);
-			retval = -EBUSY;
-			goto fail3;
+		if (udc->board.vbus_polled) {
+			udc->vbus = gpio_get_value_cansleep(udc->board.vbus_pin);
+			INIT_WORK(&udc->vbus_timer_work, at91_vbus_timer_work);
+			setup_timer(&udc->vbus_timer, at91_vbus_timer,
+				    (unsigned long)udc);		
+			mod_timer(&udc->vbus_timer,
+				  jiffies + VBUS_POLL_TIMEOUT);
+		} else {
+			udc->vbus = gpio_get_value(udc->board.vbus_pin);
+			if (request_irq(udc->board.vbus_pin, at91_vbus_irq,
+					IRQF_DISABLED, driver_name, udc)) {
+				DBG("request vbus irq %d failed\n",
+				    udc->board.vbus_pin);
+				retval = -EBUSY;
+				goto fail3;
+			}
 		}
 	} else {
 		DBG("no VBUS detection, assuming always-on\n");
@@ -1855,7 +1894,7 @@ static int at91udc_suspend(struct platform_device *pdev, pm_message_t mesg)
 		enable_irq_wake(udc->udp_irq);
 
 	udc->active_suspend = wake;
-	if (udc->board.vbus_pin > 0 && wake)
+	if (udc->board.vbus_pin > 0 && !udc->board.vbus_polled && wake)
 		enable_irq_wake(udc->board.vbus_pin);
 	return 0;
 }
@@ -1864,7 +1903,8 @@ static int at91udc_resume(struct platform_device *pdev)
 {
 	struct at91_udc *udc = platform_get_drvdata(pdev);
 
-	if (udc->board.vbus_pin > 0 && udc->active_suspend)
+	if (udc->board.vbus_pin > 0 && !udc->board.vbus_polled && 
+	    udc->active_suspend)
 		disable_irq_wake(udc->board.vbus_pin);
 
 	/* maybe reconnect to host; if so, clocks on */
diff --git a/drivers/usb/gadget/at91_udc.h b/drivers/usb/gadget/at91_udc.h
index c65d622..a1f4f54 100644
--- a/drivers/usb/gadget/at91_udc.h
+++ b/drivers/usb/gadget/at91_udc.h
@@ -144,6 +144,8 @@ struct at91_udc {
 	struct proc_dir_entry		*pde;
 	void __iomem			*udp_baseaddr;
 	int				udp_irq;
+	struct timer_list		vbus_timer;
+	struct work_struct		vbus_timer_work;
 };
 
 static inline struct at91_udc *to_udc(struct usb_gadget *g)
-- 
1.5.5.1

^ permalink raw reply related	[flat|nested] 11+ messages in thread

* [PATCH 2/3] at91_udc: Add vbus polarity and polling mode
  2010-06-28  4:39 ` [PATCH 2/3] at91_udc: Add vbus polarity and polling mode Ryan Mallon
@ 2010-06-30 21:02   ` Ryan Mallon
  2010-07-01 13:45   ` Nicolas Ferre
  1 sibling, 0 replies; 11+ messages in thread
From: Ryan Mallon @ 2010-06-30 21:02 UTC (permalink / raw)
  To: linux-arm-kernel

On 06/28/2010 04:39 PM, Ryan Mallon wrote:
> Allow the vbus signal to optionally use polling. This is required if
> the vbus signal is connected to an non-interrupting io expander for
> example. If vbus is in polling mode, then it is assumed that the vbus
> gpio may sleep. Also add an option to have vbus be an active low
> signal. Both options are set in the platform data for the device.
> 
> Signed-off-by: Ryan Mallon <ryan@bluewatersys.com>

Is anybody able to review this patch please? I have an ack for a patch
which depends on this one. This patch should have no impact (other than
slight code/data size increase) on existing users of the at91 udc driver
since it only adds an alternative code path for the case where vbus is
on a gpio which may sleep. The addition of the vbus polarity should also
not affect existing users since the default is active high.

Thanks,
~Ryan

> ---
>  arch/arm/mach-at91/include/mach/board.h |    2 +
>  drivers/usb/gadget/at91_udc.c           |   66 +++++++++++++++++++++++++------
>  drivers/usb/gadget/at91_udc.h           |    2 +
>  3 files changed, 57 insertions(+), 13 deletions(-)
> 
> diff --git a/arch/arm/mach-at91/include/mach/board.h b/arch/arm/mach-at91/include/mach/board.h
> index df2ed84..58528aa 100644
> --- a/arch/arm/mach-at91/include/mach/board.h
> +++ b/arch/arm/mach-at91/include/mach/board.h
> @@ -44,6 +44,8 @@
>   /* USB Device */
>  struct at91_udc_data {
>  	u8	vbus_pin;		/* high == host powering us */
> +	u8	vbus_active_low;	/* vbus polarity */
> +	u8	vbus_polled;		/* Use polling, not interrupt */
>  	u8	pullup_pin;		/* active == D+ pulled up */
>  	u8	pullup_active_low;	/* true == pullup_pin is active low */
>  };
> diff --git a/drivers/usb/gadget/at91_udc.c b/drivers/usb/gadget/at91_udc.c
> index eaa79c8..469a64c 100644
> --- a/drivers/usb/gadget/at91_udc.c
> +++ b/drivers/usb/gadget/at91_udc.c
> @@ -76,6 +76,7 @@
>  static const char driver_name [] = "at91_udc";
>  static const char ep0name[] = "ep0";
>  
> +#define VBUS_POLL_TIMEOUT	msecs_to_jiffies(1000)
>  
>  #define at91_udp_read(dev, reg) \
>  	__raw_readl((dev)->udp_baseaddr + (reg))
> @@ -1556,20 +1557,49 @@ static struct at91_udc controller = {
>  	/* ep6 and ep7 are also reserved (custom silicon might use them) */
>  };
>  
> +static void at91_vbus_update(struct at91_udc *udc, unsigned value)
> +{
> +	if (udc->board.vbus_active_low)
> +		value ^= 1;
> +	if (value != udc->vbus)
> +		at91_vbus_session(&udc->gadget, value);
> +}
> +
>  static irqreturn_t at91_vbus_irq(int irq, void *_udc)
>  {
>  	struct at91_udc	*udc = _udc;
> -	unsigned	value;
>  
>  	/* vbus needs at least brief debouncing */
>  	udelay(10);
> -	value = gpio_get_value(udc->board.vbus_pin);
> -	if (value != udc->vbus)
> -		at91_vbus_session(&udc->gadget, value);
> +	at91_vbus_update(udc, gpio_get_value(udc->board.vbus_pin));
>  
>  	return IRQ_HANDLED;
>  }
>  
> +static void at91_vbus_timer_work(struct work_struct *work)
> +{
> +	struct at91_udc *udc = container_of(work, struct at91_udc, 
> +					    vbus_timer_work);
> +
> +	at91_vbus_update(udc, gpio_get_value_cansleep(udc->board.vbus_pin));
> +
> +	if (!timer_pending(&udc->vbus_timer))
> +		mod_timer(&udc->vbus_timer, jiffies + VBUS_POLL_TIMEOUT);
> +}
> +
> +static void at91_vbus_timer(unsigned long data)
> +{
> +	struct at91_udc *udc = (struct at91_udc *)data;
> +
> +	/*
> +	 * If we are polling vbus it is likely that the gpio is on an
> +	 * bus such as i2c or spi which may sleep, so schedule some work
> +	 * to read the vbus gpio
> +	 */
> +	if (!work_pending(&udc->vbus_timer_work))
> +		schedule_work(&udc->vbus_timer_work);
> +}
> +
>  int usb_gadget_register_driver (struct usb_gadget_driver *driver)
>  {
>  	struct at91_udc	*udc = &controller;
> @@ -1763,13 +1793,22 @@ static int __init at91udc_probe(struct platform_device *pdev)
>  		 * Get the initial state of VBUS - we cannot expect
>  		 * a pending interrupt.
>  		 */
> -		udc->vbus = gpio_get_value(udc->board.vbus_pin);
> -		if (request_irq(udc->board.vbus_pin, at91_vbus_irq,
> -				IRQF_DISABLED, driver_name, udc)) {
> -			DBG("request vbus irq %d failed\n",
> -					udc->board.vbus_pin);
> -			retval = -EBUSY;
> -			goto fail3;
> +		if (udc->board.vbus_polled) {
> +			udc->vbus = gpio_get_value_cansleep(udc->board.vbus_pin);
> +			INIT_WORK(&udc->vbus_timer_work, at91_vbus_timer_work);
> +			setup_timer(&udc->vbus_timer, at91_vbus_timer,
> +				    (unsigned long)udc);		
> +			mod_timer(&udc->vbus_timer,
> +				  jiffies + VBUS_POLL_TIMEOUT);
> +		} else {
> +			udc->vbus = gpio_get_value(udc->board.vbus_pin);
> +			if (request_irq(udc->board.vbus_pin, at91_vbus_irq,
> +					IRQF_DISABLED, driver_name, udc)) {
> +				DBG("request vbus irq %d failed\n",
> +				    udc->board.vbus_pin);
> +				retval = -EBUSY;
> +				goto fail3;
> +			}
>  		}
>  	} else {
>  		DBG("no VBUS detection, assuming always-on\n");
> @@ -1855,7 +1894,7 @@ static int at91udc_suspend(struct platform_device *pdev, pm_message_t mesg)
>  		enable_irq_wake(udc->udp_irq);
>  
>  	udc->active_suspend = wake;
> -	if (udc->board.vbus_pin > 0 && wake)
> +	if (udc->board.vbus_pin > 0 && !udc->board.vbus_polled && wake)
>  		enable_irq_wake(udc->board.vbus_pin);
>  	return 0;
>  }
> @@ -1864,7 +1903,8 @@ static int at91udc_resume(struct platform_device *pdev)
>  {
>  	struct at91_udc *udc = platform_get_drvdata(pdev);
>  
> -	if (udc->board.vbus_pin > 0 && udc->active_suspend)
> +	if (udc->board.vbus_pin > 0 && !udc->board.vbus_polled && 
> +	    udc->active_suspend)
>  		disable_irq_wake(udc->board.vbus_pin);
>  
>  	/* maybe reconnect to host; if so, clocks on */
> diff --git a/drivers/usb/gadget/at91_udc.h b/drivers/usb/gadget/at91_udc.h
> index c65d622..a1f4f54 100644
> --- a/drivers/usb/gadget/at91_udc.h
> +++ b/drivers/usb/gadget/at91_udc.h
> @@ -144,6 +144,8 @@ struct at91_udc {
>  	struct proc_dir_entry		*pde;
>  	void __iomem			*udp_baseaddr;
>  	int				udp_irq;
> +	struct timer_list		vbus_timer;
> +	struct work_struct		vbus_timer_work;
>  };
>  
>  static inline struct at91_udc *to_udc(struct usb_gadget *g)


-- 
Bluewater Systems Ltd - ARM Technology Solution Centre

Ryan Mallon         		5 Amuri Park, 404 Barbadoes St
ryan at bluewatersys.com         	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

^ permalink raw reply	[flat|nested] 11+ messages in thread

* [PATCH 2/3] at91_udc: Add vbus polarity and polling mode
  2010-06-28  4:39 ` [PATCH 2/3] at91_udc: Add vbus polarity and polling mode Ryan Mallon
  2010-06-30 21:02   ` Ryan Mallon
@ 2010-07-01 13:45   ` Nicolas Ferre
  2010-07-02  4:40     ` Ryan Mallon
  1 sibling, 1 reply; 11+ messages in thread
From: Nicolas Ferre @ 2010-07-01 13:45 UTC (permalink / raw)
  To: linux-arm-kernel

Le 28/06/2010 06:39, Ryan Mallon :
> Allow the vbus signal to optionally use polling. This is required if
> the vbus signal is connected to an non-interrupting io expander for
> example. If vbus is in polling mode, then it is assumed that the vbus
> gpio may sleep. Also add an option to have vbus be an active low
> signal. Both options are set in the platform data for the device.
> 
> Signed-off-by: Ryan Mallon <ryan@bluewatersys.com>

Looks good, but... one question:

> @@ -1763,13 +1793,22 @@ static int __init at91udc_probe(struct platform_device *pdev)
>  		 * Get the initial state of VBUS - we cannot expect
>  		 * a pending interrupt.
>  		 */
> -		udc->vbus = gpio_get_value(udc->board.vbus_pin);
> -		if (request_irq(udc->board.vbus_pin, at91_vbus_irq,
> -				IRQF_DISABLED, driver_name, udc)) {
> -			DBG("request vbus irq %d failed\n",
> -					udc->board.vbus_pin);
> -			retval = -EBUSY;
> -			goto fail3;
> +		if (udc->board.vbus_polled) {
> +			udc->vbus = gpio_get_value_cansleep(udc->board.vbus_pin);

Shouldn't we need here something like:
udc->vbus =  (udc->board.vbus_active_low) ^ gpio_get_value_cansleep(udc->board.vbus_pin);

?

> +			INIT_WORK(&udc->vbus_timer_work, at91_vbus_timer_work);
> +			setup_timer(&udc->vbus_timer, at91_vbus_timer,
> +				    (unsigned long)udc);		
> +			mod_timer(&udc->vbus_timer,
> +				  jiffies + VBUS_POLL_TIMEOUT);
> +		} else {
> +			udc->vbus = gpio_get_value(udc->board.vbus_pin);

Ditto.

> +			if (request_irq(udc->board.vbus_pin, at91_vbus_irq,
> +					IRQF_DISABLED, driver_name, udc)) {
> +				DBG("request vbus irq %d failed\n",
> +				    udc->board.vbus_pin);
> +				retval = -EBUSY;
> +				goto fail3;
> +			}


Best regards,
-- 
Nicolas Ferre

^ permalink raw reply	[flat|nested] 11+ messages in thread

* [PATCH 2/3] at91_udc: Add vbus polarity and polling mode
  2010-07-01 13:45   ` Nicolas Ferre
@ 2010-07-02  4:40     ` Ryan Mallon
  2010-07-05 21:01       ` Ryan Mallon
  2010-07-06  8:32       ` Nicolas Ferre
  0 siblings, 2 replies; 11+ messages in thread
From: Ryan Mallon @ 2010-07-02  4:40 UTC (permalink / raw)
  To: linux-arm-kernel

On 07/02/2010 01:45 AM, Nicolas Ferre wrote:
> Le 28/06/2010 06:39, Ryan Mallon :
>   
>> Allow the vbus signal to optionally use polling. This is required if
>> the vbus signal is connected to an non-interrupting io expander for
>> example. If vbus is in polling mode, then it is assumed that the vbus
>> gpio may sleep. Also add an option to have vbus be an active low
>> signal. Both options are set in the platform data for the device.
>>
>> Signed-off-by: Ryan Mallon <ryan@bluewatersys.com>
>>     
> Looks good, but... one question:
>
>   
>> @@ -1763,13 +1793,22 @@ static int __init at91udc_probe(struct platform_device *pdev)
>>  		 * Get the initial state of VBUS - we cannot expect
>>  		 * a pending interrupt.
>>  		 */
>> -		udc->vbus = gpio_get_value(udc->board.vbus_pin);
>> -		if (request_irq(udc->board.vbus_pin, at91_vbus_irq,
>> -				IRQF_DISABLED, driver_name, udc)) {
>> -			DBG("request vbus irq %d failed\n",
>> -					udc->board.vbus_pin);
>> -			retval = -EBUSY;
>> -			goto fail3;
>> +		if (udc->board.vbus_polled) {
>> +			udc->vbus = gpio_get_value_cansleep(udc->board.vbus_pin);
>>     
> Shouldn't we need here something like:
> udc->vbus =  (udc->board.vbus_active_low) ^ gpio_get_value_cansleep(udc->board.vbus_pin);
>   

Yes, thanks. The updated patch below fixes it. Also simplify
at91_vbus_update (always do the xor) and move the initial setting of
udc->vbus outside of the udc->board.vbus_polled test, since we can use
gpio_get_value_cansleep in both cases.

Signed-off-by: Ryan Mallon <ryan@bluewatersys.com>
---

diff --git a/arch/arm/mach-at91/include/mach/board.h b/arch/arm/mach-at91/include/mach/board.h
index df2ed84..58528aa 100644
--- a/arch/arm/mach-at91/include/mach/board.h
+++ b/arch/arm/mach-at91/include/mach/board.h
@@ -44,6 +44,8 @@
  /* USB Device */
 struct at91_udc_data {
 	u8	vbus_pin;		/* high == host powering us */
+	u8	vbus_active_low;	/* vbus polarity */
+	u8	vbus_polled;		/* Use polling, not interrupt */
 	u8	pullup_pin;		/* active == D+ pulled up */
 	u8	pullup_active_low;	/* true == pullup_pin is active low */
 };
diff --git a/drivers/usb/gadget/at91_udc.c b/drivers/usb/gadget/at91_udc.c
index eaa79c8..be36f2f 100644
--- a/drivers/usb/gadget/at91_udc.c
+++ b/drivers/usb/gadget/at91_udc.c
@@ -76,6 +76,7 @@
 static const char driver_name [] = "at91_udc";
 static const char ep0name[] = "ep0";
 
+#define VBUS_POLL_TIMEOUT	msecs_to_jiffies(1000)
 
 #define at91_udp_read(dev, reg) \
 	__raw_readl((dev)->udp_baseaddr + (reg))
@@ -1556,20 +1557,48 @@ static struct at91_udc controller = {
 	/* ep6 and ep7 are also reserved (custom silicon might use them) */
 };
 
+static void at91_vbus_update(struct at91_udc *udc, unsigned value)
+{
+	value ^= udc->board.vbus_active_low;
+	if (value != udc->vbus)
+		at91_vbus_session(&udc->gadget, value);
+}
+
 static irqreturn_t at91_vbus_irq(int irq, void *_udc)
 {
 	struct at91_udc	*udc = _udc;
-	unsigned	value;
 
 	/* vbus needs at least brief debouncing */
 	udelay(10);
-	value = gpio_get_value(udc->board.vbus_pin);
-	if (value != udc->vbus)
-		at91_vbus_session(&udc->gadget, value);
+	at91_vbus_update(udc, gpio_get_value(udc->board.vbus_pin));
 
 	return IRQ_HANDLED;
 }
 
+static void at91_vbus_timer_work(struct work_struct *work)
+{
+	struct at91_udc *udc = container_of(work, struct at91_udc, 
+					    vbus_timer_work);
+
+	at91_vbus_update(udc, gpio_get_value_cansleep(udc->board.vbus_pin));
+
+	if (!timer_pending(&udc->vbus_timer))
+		mod_timer(&udc->vbus_timer, jiffies + VBUS_POLL_TIMEOUT);
+}
+
+static void at91_vbus_timer(unsigned long data)
+{
+	struct at91_udc *udc = (struct at91_udc *)data;
+
+	/*
+	 * If we are polling vbus it is likely that the gpio is on an
+	 * bus such as i2c or spi which may sleep, so schedule some work
+	 * to read the vbus gpio
+	 */
+	if (!work_pending(&udc->vbus_timer_work))
+		schedule_work(&udc->vbus_timer_work);
+}
+
 int usb_gadget_register_driver (struct usb_gadget_driver *driver)
 {
 	struct at91_udc	*udc = &controller;
@@ -1763,13 +1792,23 @@ static int __init at91udc_probe(struct platform_device *pdev)
 		 * Get the initial state of VBUS - we cannot expect
 		 * a pending interrupt.
 		 */
-		udc->vbus = gpio_get_value(udc->board.vbus_pin);
-		if (request_irq(udc->board.vbus_pin, at91_vbus_irq,
-				IRQF_DISABLED, driver_name, udc)) {
-			DBG("request vbus irq %d failed\n",
-					udc->board.vbus_pin);
-			retval = -EBUSY;
-			goto fail3;
+		udc->vbus = gpio_get_value_cansleep(udc->board.vbus_pin) ^
+			udc->board.vbus_active_low;
+
+		if (udc->board.vbus_polled) {
+			INIT_WORK(&udc->vbus_timer_work, at91_vbus_timer_work);
+			setup_timer(&udc->vbus_timer, at91_vbus_timer,
+				    (unsigned long)udc);		
+			mod_timer(&udc->vbus_timer,
+				  jiffies + VBUS_POLL_TIMEOUT);
+		} else {
+			if (request_irq(udc->board.vbus_pin, at91_vbus_irq,
+					IRQF_DISABLED, driver_name, udc)) {
+				DBG("request vbus irq %d failed\n",
+				    udc->board.vbus_pin);
+				retval = -EBUSY;
+				goto fail3;
+			}
 		}
 	} else {
 		DBG("no VBUS detection, assuming always-on\n");
@@ -1855,7 +1894,7 @@ static int at91udc_suspend(struct platform_device *pdev, pm_message_t mesg)
 		enable_irq_wake(udc->udp_irq);
 
 	udc->active_suspend = wake;
-	if (udc->board.vbus_pin > 0 && wake)
+	if (udc->board.vbus_pin > 0 && !udc->board.vbus_polled && wake)
 		enable_irq_wake(udc->board.vbus_pin);
 	return 0;
 }
@@ -1864,7 +1903,8 @@ static int at91udc_resume(struct platform_device *pdev)
 {
 	struct at91_udc *udc = platform_get_drvdata(pdev);
 
-	if (udc->board.vbus_pin > 0 && udc->active_suspend)
+	if (udc->board.vbus_pin > 0 && !udc->board.vbus_polled && 
+	    udc->active_suspend)
 		disable_irq_wake(udc->board.vbus_pin);
 
 	/* maybe reconnect to host; if so, clocks on */
diff --git a/drivers/usb/gadget/at91_udc.h b/drivers/usb/gadget/at91_udc.h
index c65d622..a1f4f54 100644
--- a/drivers/usb/gadget/at91_udc.h
+++ b/drivers/usb/gadget/at91_udc.h
@@ -144,6 +144,8 @@ struct at91_udc {
 	struct proc_dir_entry		*pde;
 	void __iomem			*udp_baseaddr;
 	int				udp_irq;
+	struct timer_list		vbus_timer;
+	struct work_struct		vbus_timer_work;
 };
 
 static inline struct at91_udc *to_udc(struct usb_gadget *g)

^ permalink raw reply related	[flat|nested] 11+ messages in thread

* [PATCH 2/3] at91_udc: Add vbus polarity and polling mode
  2010-07-02  4:40     ` Ryan Mallon
@ 2010-07-05 21:01       ` Ryan Mallon
  2010-07-06  8:32       ` Nicolas Ferre
  1 sibling, 0 replies; 11+ messages in thread
From: Ryan Mallon @ 2010-07-05 21:01 UTC (permalink / raw)
  To: linux-arm-kernel

On 07/02/2010 04:40 PM, Ryan Mallon wrote:
> On 07/02/2010 01:45 AM, Nicolas Ferre wrote:
>> Le 28/06/2010 06:39, Ryan Mallon :
>>   
>>> +		if (udc->board.vbus_polled) {
>>> +			udc->vbus = gpio_get_value_cansleep(udc->board.vbus_pin);
>>>     
>> Shouldn't we need here something like:
>> udc->vbus =  (udc->board.vbus_active_low) ^ gpio_get_value_cansleep(udc->board.vbus_pin);
>>   
> 
> Yes, thanks. The updated patch below fixes it. Also simplify
> at91_vbus_update (always do the xor) and move the initial setting of
> udc->vbus outside of the udc->board.vbus_polled test, since we can use
> gpio_get_value_cansleep in both cases.

Nicolas, can I get your ack on this now to put this through to the patch
system please?

~Ryan

> Signed-off-by: Ryan Mallon <ryan@bluewatersys.com>
> ---
> 
> diff --git a/arch/arm/mach-at91/include/mach/board.h b/arch/arm/mach-at91/include/mach/board.h
> index df2ed84..58528aa 100644
> --- a/arch/arm/mach-at91/include/mach/board.h
> +++ b/arch/arm/mach-at91/include/mach/board.h
> @@ -44,6 +44,8 @@
>   /* USB Device */
>  struct at91_udc_data {
>  	u8	vbus_pin;		/* high == host powering us */
> +	u8	vbus_active_low;	/* vbus polarity */
> +	u8	vbus_polled;		/* Use polling, not interrupt */
>  	u8	pullup_pin;		/* active == D+ pulled up */
>  	u8	pullup_active_low;	/* true == pullup_pin is active low */
>  };
> diff --git a/drivers/usb/gadget/at91_udc.c b/drivers/usb/gadget/at91_udc.c
> index eaa79c8..be36f2f 100644
> --- a/drivers/usb/gadget/at91_udc.c
> +++ b/drivers/usb/gadget/at91_udc.c
> @@ -76,6 +76,7 @@
>  static const char driver_name [] = "at91_udc";
>  static const char ep0name[] = "ep0";
>  
> +#define VBUS_POLL_TIMEOUT	msecs_to_jiffies(1000)
>  
>  #define at91_udp_read(dev, reg) \
>  	__raw_readl((dev)->udp_baseaddr + (reg))
> @@ -1556,20 +1557,48 @@ static struct at91_udc controller = {
>  	/* ep6 and ep7 are also reserved (custom silicon might use them) */
>  };
>  
> +static void at91_vbus_update(struct at91_udc *udc, unsigned value)
> +{
> +	value ^= udc->board.vbus_active_low;
> +	if (value != udc->vbus)
> +		at91_vbus_session(&udc->gadget, value);
> +}
> +
>  static irqreturn_t at91_vbus_irq(int irq, void *_udc)
>  {
>  	struct at91_udc	*udc = _udc;
> -	unsigned	value;
>  
>  	/* vbus needs at least brief debouncing */
>  	udelay(10);
> -	value = gpio_get_value(udc->board.vbus_pin);
> -	if (value != udc->vbus)
> -		at91_vbus_session(&udc->gadget, value);
> +	at91_vbus_update(udc, gpio_get_value(udc->board.vbus_pin));
>  
>  	return IRQ_HANDLED;
>  }
>  
> +static void at91_vbus_timer_work(struct work_struct *work)
> +{
> +	struct at91_udc *udc = container_of(work, struct at91_udc, 
> +					    vbus_timer_work);
> +
> +	at91_vbus_update(udc, gpio_get_value_cansleep(udc->board.vbus_pin));
> +
> +	if (!timer_pending(&udc->vbus_timer))
> +		mod_timer(&udc->vbus_timer, jiffies + VBUS_POLL_TIMEOUT);
> +}
> +
> +static void at91_vbus_timer(unsigned long data)
> +{
> +	struct at91_udc *udc = (struct at91_udc *)data;
> +
> +	/*
> +	 * If we are polling vbus it is likely that the gpio is on an
> +	 * bus such as i2c or spi which may sleep, so schedule some work
> +	 * to read the vbus gpio
> +	 */
> +	if (!work_pending(&udc->vbus_timer_work))
> +		schedule_work(&udc->vbus_timer_work);
> +}
> +
>  int usb_gadget_register_driver (struct usb_gadget_driver *driver)
>  {
>  	struct at91_udc	*udc = &controller;
> @@ -1763,13 +1792,23 @@ static int __init at91udc_probe(struct platform_device *pdev)
>  		 * Get the initial state of VBUS - we cannot expect
>  		 * a pending interrupt.
>  		 */
> -		udc->vbus = gpio_get_value(udc->board.vbus_pin);
> -		if (request_irq(udc->board.vbus_pin, at91_vbus_irq,
> -				IRQF_DISABLED, driver_name, udc)) {
> -			DBG("request vbus irq %d failed\n",
> -					udc->board.vbus_pin);
> -			retval = -EBUSY;
> -			goto fail3;
> +		udc->vbus = gpio_get_value_cansleep(udc->board.vbus_pin) ^
> +			udc->board.vbus_active_low;
> +
> +		if (udc->board.vbus_polled) {
> +			INIT_WORK(&udc->vbus_timer_work, at91_vbus_timer_work);
> +			setup_timer(&udc->vbus_timer, at91_vbus_timer,
> +				    (unsigned long)udc);		
> +			mod_timer(&udc->vbus_timer,
> +				  jiffies + VBUS_POLL_TIMEOUT);
> +		} else {
> +			if (request_irq(udc->board.vbus_pin, at91_vbus_irq,
> +					IRQF_DISABLED, driver_name, udc)) {
> +				DBG("request vbus irq %d failed\n",
> +				    udc->board.vbus_pin);
> +				retval = -EBUSY;
> +				goto fail3;
> +			}
>  		}
>  	} else {
>  		DBG("no VBUS detection, assuming always-on\n");
> @@ -1855,7 +1894,7 @@ static int at91udc_suspend(struct platform_device *pdev, pm_message_t mesg)
>  		enable_irq_wake(udc->udp_irq);
>  
>  	udc->active_suspend = wake;
> -	if (udc->board.vbus_pin > 0 && wake)
> +	if (udc->board.vbus_pin > 0 && !udc->board.vbus_polled && wake)
>  		enable_irq_wake(udc->board.vbus_pin);
>  	return 0;
>  }
> @@ -1864,7 +1903,8 @@ static int at91udc_resume(struct platform_device *pdev)
>  {
>  	struct at91_udc *udc = platform_get_drvdata(pdev);
>  
> -	if (udc->board.vbus_pin > 0 && udc->active_suspend)
> +	if (udc->board.vbus_pin > 0 && !udc->board.vbus_polled && 
> +	    udc->active_suspend)
>  		disable_irq_wake(udc->board.vbus_pin);
>  
>  	/* maybe reconnect to host; if so, clocks on */
> diff --git a/drivers/usb/gadget/at91_udc.h b/drivers/usb/gadget/at91_udc.h
> index c65d622..a1f4f54 100644
> --- a/drivers/usb/gadget/at91_udc.h
> +++ b/drivers/usb/gadget/at91_udc.h
> @@ -144,6 +144,8 @@ struct at91_udc {
>  	struct proc_dir_entry		*pde;
>  	void __iomem			*udp_baseaddr;
>  	int				udp_irq;
> +	struct timer_list		vbus_timer;
> +	struct work_struct		vbus_timer_work;
>  };
>  
>  static inline struct at91_udc *to_udc(struct usb_gadget *g)
> 
> 
> 
> 
> _______________________________________________
> linux-arm-kernel mailing list
> linux-arm-kernel at lists.infradead.org
> http://lists.infradead.org/mailman/listinfo/linux-arm-kernel


-- 
Bluewater Systems Ltd - ARM Technology Solution Centre

Ryan Mallon         		5 Amuri Park, 404 Barbadoes St
ryan at bluewatersys.com         	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

^ permalink raw reply	[flat|nested] 11+ messages in thread

* [PATCH 2/3] at91_udc: Add vbus polarity and polling mode
  2010-07-02  4:40     ` Ryan Mallon
  2010-07-05 21:01       ` Ryan Mallon
@ 2010-07-06  8:32       ` Nicolas Ferre
  1 sibling, 0 replies; 11+ messages in thread
From: Nicolas Ferre @ 2010-07-06  8:32 UTC (permalink / raw)
  To: linux-arm-kernel

Le 02/07/2010 06:40, Ryan Mallon :
> On 07/02/2010 01:45 AM, Nicolas Ferre wrote:
>> Le 28/06/2010 06:39, Ryan Mallon :
>>   
>>> Allow the vbus signal to optionally use polling. This is required if
>>> the vbus signal is connected to an non-interrupting io expander for
>>> example. If vbus is in polling mode, then it is assumed that the vbus
>>> gpio may sleep. Also add an option to have vbus be an active low
>>> signal. Both options are set in the platform data for the device.
>>>
>>> Signed-off-by: Ryan Mallon <ryan@bluewatersys.com>
>>>     
>> Looks good, but... one question:
>>
>>   
>>> @@ -1763,13 +1793,22 @@ static int __init at91udc_probe(struct platform_device *pdev)
>>>  		 * Get the initial state of VBUS - we cannot expect
>>>  		 * a pending interrupt.
>>>  		 */
>>> -		udc->vbus = gpio_get_value(udc->board.vbus_pin);
>>> -		if (request_irq(udc->board.vbus_pin, at91_vbus_irq,
>>> -				IRQF_DISABLED, driver_name, udc)) {
>>> -			DBG("request vbus irq %d failed\n",
>>> -					udc->board.vbus_pin);
>>> -			retval = -EBUSY;
>>> -			goto fail3;
>>> +		if (udc->board.vbus_polled) {
>>> +			udc->vbus = gpio_get_value_cansleep(udc->board.vbus_pin);
>>>     
>> Shouldn't we need here something like:
>> udc->vbus =  (udc->board.vbus_active_low) ^ gpio_get_value_cansleep(udc->board.vbus_pin);
>>   
> 
> Yes, thanks. The updated patch below fixes it. Also simplify
> at91_vbus_update (always do the xor) and move the initial setting of
> udc->vbus outside of the udc->board.vbus_polled test, since we can use
> gpio_get_value_cansleep in both cases.
> 
> Signed-off-by: Ryan Mallon <ryan@bluewatersys.com>

Acked-by: Nicolas Ferre <nicolas.ferre@atmel.com>

> ---
> 
> diff --git a/arch/arm/mach-at91/include/mach/board.h b/arch/arm/mach-at91/include/mach/board.h
> index df2ed84..58528aa 100644
> --- a/arch/arm/mach-at91/include/mach/board.h
> +++ b/arch/arm/mach-at91/include/mach/board.h
> @@ -44,6 +44,8 @@
>   /* USB Device */
>  struct at91_udc_data {
>  	u8	vbus_pin;		/* high == host powering us */
> +	u8	vbus_active_low;	/* vbus polarity */
> +	u8	vbus_polled;		/* Use polling, not interrupt */
>  	u8	pullup_pin;		/* active == D+ pulled up */
>  	u8	pullup_active_low;	/* true == pullup_pin is active low */
>  };
> diff --git a/drivers/usb/gadget/at91_udc.c b/drivers/usb/gadget/at91_udc.c
> index eaa79c8..be36f2f 100644
> --- a/drivers/usb/gadget/at91_udc.c
> +++ b/drivers/usb/gadget/at91_udc.c
> @@ -76,6 +76,7 @@
>  static const char driver_name [] = "at91_udc";
>  static const char ep0name[] = "ep0";
>  
> +#define VBUS_POLL_TIMEOUT	msecs_to_jiffies(1000)
>  
>  #define at91_udp_read(dev, reg) \
>  	__raw_readl((dev)->udp_baseaddr + (reg))
> @@ -1556,20 +1557,48 @@ static struct at91_udc controller = {
>  	/* ep6 and ep7 are also reserved (custom silicon might use them) */
>  };
>  
> +static void at91_vbus_update(struct at91_udc *udc, unsigned value)
> +{
> +	value ^= udc->board.vbus_active_low;
> +	if (value != udc->vbus)
> +		at91_vbus_session(&udc->gadget, value);
> +}
> +
>  static irqreturn_t at91_vbus_irq(int irq, void *_udc)
>  {
>  	struct at91_udc	*udc = _udc;
> -	unsigned	value;
>  
>  	/* vbus needs at least brief debouncing */
>  	udelay(10);
> -	value = gpio_get_value(udc->board.vbus_pin);
> -	if (value != udc->vbus)
> -		at91_vbus_session(&udc->gadget, value);
> +	at91_vbus_update(udc, gpio_get_value(udc->board.vbus_pin));
>  
>  	return IRQ_HANDLED;
>  }
>  
> +static void at91_vbus_timer_work(struct work_struct *work)
> +{
> +	struct at91_udc *udc = container_of(work, struct at91_udc, 
> +					    vbus_timer_work);
> +
> +	at91_vbus_update(udc, gpio_get_value_cansleep(udc->board.vbus_pin));
> +
> +	if (!timer_pending(&udc->vbus_timer))
> +		mod_timer(&udc->vbus_timer, jiffies + VBUS_POLL_TIMEOUT);
> +}
> +
> +static void at91_vbus_timer(unsigned long data)
> +{
> +	struct at91_udc *udc = (struct at91_udc *)data;
> +
> +	/*
> +	 * If we are polling vbus it is likely that the gpio is on an
> +	 * bus such as i2c or spi which may sleep, so schedule some work
> +	 * to read the vbus gpio
> +	 */
> +	if (!work_pending(&udc->vbus_timer_work))
> +		schedule_work(&udc->vbus_timer_work);
> +}
> +
>  int usb_gadget_register_driver (struct usb_gadget_driver *driver)
>  {
>  	struct at91_udc	*udc = &controller;
> @@ -1763,13 +1792,23 @@ static int __init at91udc_probe(struct platform_device *pdev)
>  		 * Get the initial state of VBUS - we cannot expect
>  		 * a pending interrupt.
>  		 */
> -		udc->vbus = gpio_get_value(udc->board.vbus_pin);
> -		if (request_irq(udc->board.vbus_pin, at91_vbus_irq,
> -				IRQF_DISABLED, driver_name, udc)) {
> -			DBG("request vbus irq %d failed\n",
> -					udc->board.vbus_pin);
> -			retval = -EBUSY;
> -			goto fail3;
> +		udc->vbus = gpio_get_value_cansleep(udc->board.vbus_pin) ^
> +			udc->board.vbus_active_low;
> +
> +		if (udc->board.vbus_polled) {
> +			INIT_WORK(&udc->vbus_timer_work, at91_vbus_timer_work);
> +			setup_timer(&udc->vbus_timer, at91_vbus_timer,
> +				    (unsigned long)udc);		
> +			mod_timer(&udc->vbus_timer,
> +				  jiffies + VBUS_POLL_TIMEOUT);
> +		} else {
> +			if (request_irq(udc->board.vbus_pin, at91_vbus_irq,
> +					IRQF_DISABLED, driver_name, udc)) {
> +				DBG("request vbus irq %d failed\n",
> +				    udc->board.vbus_pin);
> +				retval = -EBUSY;
> +				goto fail3;
> +			}
>  		}
>  	} else {
>  		DBG("no VBUS detection, assuming always-on\n");
> @@ -1855,7 +1894,7 @@ static int at91udc_suspend(struct platform_device *pdev, pm_message_t mesg)
>  		enable_irq_wake(udc->udp_irq);
>  
>  	udc->active_suspend = wake;
> -	if (udc->board.vbus_pin > 0 && wake)
> +	if (udc->board.vbus_pin > 0 && !udc->board.vbus_polled && wake)
>  		enable_irq_wake(udc->board.vbus_pin);
>  	return 0;
>  }
> @@ -1864,7 +1903,8 @@ static int at91udc_resume(struct platform_device *pdev)
>  {
>  	struct at91_udc *udc = platform_get_drvdata(pdev);
>  
> -	if (udc->board.vbus_pin > 0 && udc->active_suspend)
> +	if (udc->board.vbus_pin > 0 && !udc->board.vbus_polled && 
> +	    udc->active_suspend)
>  		disable_irq_wake(udc->board.vbus_pin);
>  
>  	/* maybe reconnect to host; if so, clocks on */
> diff --git a/drivers/usb/gadget/at91_udc.h b/drivers/usb/gadget/at91_udc.h
> index c65d622..a1f4f54 100644
> --- a/drivers/usb/gadget/at91_udc.h
> +++ b/drivers/usb/gadget/at91_udc.h
> @@ -144,6 +144,8 @@ struct at91_udc {
>  	struct proc_dir_entry		*pde;
>  	void __iomem			*udp_baseaddr;
>  	int				udp_irq;
> +	struct timer_list		vbus_timer;
> +	struct work_struct		vbus_timer_work;
>  };
>  
>  static inline struct at91_udc *to_udc(struct usb_gadget *g)
> 
> 
> 
> 


-- 
Nicolas Ferre

^ permalink raw reply	[flat|nested] 11+ messages in thread

end of thread, other threads:[~2010-07-06  8:32 UTC | newest]

Thread overview: 11+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2010-06-16 21:20 [PATCH 0/3] at91: Add support for Snapper 9260/9G20 modules Ryan Mallon
2010-06-16 21:20 ` [PATCH 1/3] AT91: Define NR_BUILTIN_GPIO Ryan Mallon
2010-06-16 21:20 ` [PATCH 2/3] at91_udc: Add vbus polarity and polling mode Ryan Mallon
2010-06-17 22:03   ` Ryan Mallon
2010-06-16 21:20 ` [PATCH 3/3] at91: Add support for Bluewater Systems Snapper 9260/9G20 modules Ryan Mallon
  -- strict thread matches above, loose matches on Subject: below --
2010-06-28  4:39 [PATCH 0/3] " Ryan Mallon
2010-06-28  4:39 ` [PATCH 2/3] at91_udc: Add vbus polarity and polling mode Ryan Mallon
2010-06-30 21:02   ` Ryan Mallon
2010-07-01 13:45   ` Nicolas Ferre
2010-07-02  4:40     ` Ryan Mallon
2010-07-05 21:01       ` Ryan Mallon
2010-07-06  8:32       ` Nicolas Ferre

This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).