summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c16
-rw-r--r--nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c18
-rw-r--r--nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c51
-rw-r--r--nuttx/arch/arm/src/lpc43xx/lpc43_usb0dev.c46
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_otgfsdev.c23
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_usbdev.c14
-rw-r--r--nuttx/arch/avr/src/at90usb/at90usb_usbdev.c16
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-usbdev.c19
8 files changed, 181 insertions, 22 deletions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c b/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c
index b1ddb5928..753f82326 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c
@@ -2175,6 +2175,22 @@ static int lpc17_usbinterrupt(int irq, FAR void *context)
{
usbtrace(TRACE_INTDECODE(LPC17_TRACEINTID_SUSPENDCHG),
(uint16_t)g_usbdev.devstatus);
+
+ /* Inform the Class driver of the change */
+
+ if (priv->driver)
+ {
+ if (DEVSTATUS_SUSPEND(g_usbdev.devstatus))
+ {
+ CLASS_SUSPEND(priv->driver, &priv->usbdev);
+ }
+ else
+ {
+ CLASS_RESUME(priv->driver, &priv->usbdev);
+ }
+ }
+
+ /* TODO: Perform power management operations here. */
}
/* Device reset */
diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c b/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c
index 78a5fe1c3..78dc86992 100644
--- a/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c
+++ b/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c
@@ -1,7 +1,7 @@
/*******************************************************************************
* arch/arm/src/lpc214x/lpc214x_usbdev.c
*
- * Copyright (C) 2008-2010, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2010, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -2139,6 +2139,22 @@ static int lpc214x_usbinterrupt(int irq, FAR void *context)
{
usbtrace(TRACE_INTDECODE(LPC214X_TRACEINTID_SUSPENDCHG),
(uint16_t)g_usbdev.devstatus);
+
+ /* Inform the Class driver of the change */
+
+ if (priv->driver)
+ {
+ if (DEVSTATUS_SUSPEND(g_usbdev.devstatus))
+ {
+ CLASS_SUSPEND(priv->driver, &priv->usbdev);
+ }
+ else
+ {
+ CLASS_RESUME(priv->driver, &priv->usbdev);
+ }
+ }
+
+ /* TODO: Perform power management operations here. */
}
/* Device reset */
diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c b/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c
index 386abb5b8..ddeb1bf6b 100644
--- a/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c
+++ b/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c
@@ -6,7 +6,7 @@
*
* Part of the NuttX OS and based, in part, on the LPC2148 USB driver:
*
- * Copyright (C) 2010-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -160,8 +160,9 @@
#define LPC31_TRACEINTID_IFGETSTATUS 0x0015
#define LPC31_TRACEINTID_SETCONFIG 0x0016
#define LPC31_TRACEINTID_SETFEATURE 0x0017
-#define LPC31_TRACEINTID_SUSPENDCHG 0x0018
-#define LPC31_TRACEINTID_SYNCHFRAME 0x0019
+#define LPC31_TRACEINTID_SUSPENDED 0x0018
+#define LPC31_TRACEINTID_RESUMED 0x0019
+#define LPC31_TRACEINTID_SYNCHFRAME 0x001a
/* Hardware interface **********************************************************/
@@ -309,6 +310,7 @@ struct lpc31_usbdev_s
uint8_t selfpowered:1; /* 1: Device is self powered */
uint8_t paddrset:1; /* 1: Peripheral addr has been set */
uint8_t attached:1; /* 1: Host attached */
+ uint8_t suspended:1; /* 1: Suspended */
uint32_t softprio; /* Bitset of high priority interrupts */
uint32_t epavail; /* Bitset of available endpoints */
#ifdef CONFIG_LPC31_USBDEV_FRAME_INTERRUPT
@@ -1065,7 +1067,9 @@ static void lpc31_usbreset(struct lpc31_usbdev_s *priv)
* driver should then accept any new configurations. */
if (priv->driver)
+ {
CLASS_DISCONNECT(priv->driver, &priv->usbdev);
+ }
/* Set the interrupt Threshold control interval to 0 */
lpc31_chgbits(USBDEV_USBCMD_ITC_MASK, USBDEV_USBCMD_ITCIMME, LPC31_USBDEV_USBCMD);
@@ -1649,6 +1653,7 @@ static int lpc31_usbinterrupt(int irq, FAR void *context)
usbtrace(TRACE_INTENTRY(LPC31_TRACEINTID_USB), 0);
/* Read the interrupts and then clear them */
+
disr = lpc31_getreg(LPC31_USBDEV_USBSTS);
lpc31_putreg(disr, LPC31_USBDEV_USBSTS);
@@ -1661,11 +1666,43 @@ static int lpc31_usbinterrupt(int irq, FAR void *context)
usbtrace(TRACE_INTEXIT(LPC31_TRACEINTID_USB), 0);
return OK;
}
-
- if (disr & USBDEV_USBSTS_SLI)
+
+ /* When the device controller enters a suspend state from an active state,
+ * the SLI bit will be set to a one.
+ */
+
+ if (!priv->suspended && (disr & USBDEV_USBSTS_SLI) != 0)
{
- // FIXME: what do we need to do here...
- usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_SUSPENDCHG),0);
+ usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_SUSPENDED),0);
+
+ /* Inform the Class driver of the suspend event */
+
+ priv->suspended = 1;
+ if (priv->driver)
+ {
+ CLASS_SUSPEND(priv->driver, &priv->usbdev);
+ }
+
+ /* TODO: Perform power management operations here. */
+ }
+
+ /* The device controller clears the SLI bit upon exiting from a suspend
+ * state. This bit can also be cleared by software writing a one to it.
+ */
+
+ else if (priv->suspended && (disr & USBDEV_USBSTS_SLI) == 0)
+ {
+ usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_RESUMED),0);
+
+ /* Inform the Class driver of the resume event */
+
+ priv->suspended = 0;
+ if (priv->driver)
+ {
+ CLASS_RESUME(priv->driver, &priv->usbdev);
+ }
+
+ /* TODO: Perform power management operations here. */
}
if (disr & USBDEV_USBSTS_PCI)
diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_usb0dev.c b/nuttx/arch/arm/src/lpc43xx/lpc43_usb0dev.c
index a40d6492d..d0af116d6 100644
--- a/nuttx/arch/arm/src/lpc43xx/lpc43_usb0dev.c
+++ b/nuttx/arch/arm/src/lpc43xx/lpc43_usb0dev.c
@@ -1,7 +1,7 @@
/*******************************************************************************
* arch/arm/src/lpc43xx/lpc43_usbdev.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Part of the NuttX OS and based, in part, on the LPC31xx USB driver:
@@ -163,8 +163,9 @@
#define LPC43_TRACEINTID_IFGETSTATUS 0x0015
#define LPC43_TRACEINTID_SETCONFIG 0x0016
#define LPC43_TRACEINTID_SETFEATURE 0x0017
-#define LPC43_TRACEINTID_SUSPENDCHG 0x0018
-#define LPC43_TRACEINTID_SYNCHFRAME 0x0019
+#define LPC43_TRACEINTID_SUSPENDED 0x0018
+#define LPC43_TRACEINTID_RESUMED 0x0019
+#define LPC43_TRACEINTID_SYNCHFRAME 0x001a
/* Hardware interface **********************************************************/
@@ -312,6 +313,7 @@ struct lpc43_usbdev_s
uint8_t selfpowered:1; /* 1: Device is self powered */
uint8_t paddrset:1; /* 1: Peripheral addr has been set */
uint8_t attached:1; /* 1: Host attached */
+ uint8_t suspended:1; /* 1: Suspended */
uint32_t softprio; /* Bitset of high priority interrupts */
uint32_t epavail; /* Bitset of available endpoints */
#ifdef CONFIG_LPC43_USBDEV_FRAME_INTERRUPT
@@ -1665,10 +1667,42 @@ static int lpc43_usbinterrupt(int irq, FAR void *context)
return OK;
}
- if (disr & USBDEV_USBSTS_SLI)
+ /* When the device controller enters a suspend state from an active state,
+ * the SLI bit will be set to a one.
+ */
+
+ if (!priv->suspended && (disr & USBDEV_USBSTS_SLI) != 0)
+ {
+ usbtrace(TRACE_INTDECODE(LPC43_TRACEINTID_SUSPENDED),0);
+
+ /* Inform the Class driver of the suspend event */
+
+ priv->suspended = 1;
+ if (priv->driver)
+ {
+ CLASS_SUSPEND(priv->driver, &priv->usbdev);
+ }
+
+ /* TODO: Perform power management operations here. */
+ }
+
+ /* The device controller clears the SLI bit upon exiting from a suspend
+ * state. This bit can also be cleared by software writing a one to it.
+ */
+
+ else if (priv->suspended && (disr & USBDEV_USBSTS_SLI) == 0)
{
- // FIXME: what do we need to do here...
- usbtrace(TRACE_INTDECODE(LPC43_TRACEINTID_SUSPENDCHG),0);
+ usbtrace(TRACE_INTDECODE(LPC43_TRACEINTID_RESUMED),0);
+
+ /* Inform the Class driver of the resume event */
+
+ priv->suspended = 0;
+ if (priv->driver)
+ {
+ CLASS_RESUME(priv->driver, &priv->usbdev);
+ }
+
+ /* TODO: Perform power management operations here. */
}
if (disr & USBDEV_USBSTS_PCI)
diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
index a2de6d138..bcce3ce60 100644
--- a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
+++ b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
@@ -424,7 +424,6 @@ struct stm32_usbdev_s
uint8_t stalled:1; /* 1: Protocol stalled */
uint8_t selfpowered:1; /* 1: Device is self powered */
- uint8_t connected:1; /* 1: Host connected */
uint8_t addressed:1; /* 1: Peripheral address has been set */
uint8_t configured:1; /* 1: Class driver has been configured */
uint8_t wakeup:1; /* 1: Device remote wake-up */
@@ -1074,8 +1073,6 @@ static void stm32_epin_request(FAR struct stm32_usbdev_s *priv,
struct stm32_req_s *privreq;
uint32_t regaddr;
uint32_t regval;
- int32_t timeout;
- int avail;
uint8_t *buf;
int nbytes;
int nwords;
@@ -2874,6 +2871,13 @@ static inline void stm32_resumeinterrupt(FAR struct stm32_usbdev_s *priv)
/* Restore full power -- whatever that means for this particular board */
stm32_usbsuspend((struct usbdev_s *)priv, true);
+
+ /* Notify the class driver of the resume event */
+
+ if (priv->driver)
+ {
+ CLASS_RESUME(priv->driver, &priv->usbdev);
+ }
}
/*******************************************************************************
@@ -2888,7 +2892,16 @@ static inline void stm32_suspendinterrupt(FAR struct stm32_usbdev_s *priv)
{
#ifdef CONFIG_USBDEV_LOWPOWER
uint32_t regval;
+#endif
+ /* Notify the class driver of the suspend event */
+
+ if (priv->driver)
+ {
+ CLASS_SUSPEND(priv->driver, &priv->usbdev);
+ }
+
+#ifdef CONFIG_USBDEV_LOWPOWER
/* OTGFS_DSTS_SUSPSTS is set as long as the suspend condition is detected
* on USB. Check if we are still have the suspend condition, that we are
* connected to the host, and that we have been configured.
@@ -2896,9 +2909,7 @@ static inline void stm32_suspendinterrupt(FAR struct stm32_usbdev_s *priv)
regval = stm32_getreg(STM32_OTGFS_DSTS);
- if ((regval & OTGFS_DSTS_SUSPSTS) != 0 &&
- priv->connected &&
- devstate == DEVSTATE_CONFIGURED)
+ if ((regval & OTGFS_DSTS_SUSPSTS) != 0 && devstate == DEVSTATE_CONFIGURED)
{
/* Switch off OTG FS clocking. Setting OTGFS_PCGCCTL_STPPCLK stops the
* PHY clock.
diff --git a/nuttx/arch/arm/src/stm32/stm32_usbdev.c b/nuttx/arch/arm/src/stm32/stm32_usbdev.c
index 602de3824..d13ac8f96 100644
--- a/nuttx/arch/arm/src/stm32/stm32_usbdev.c
+++ b/nuttx/arch/arm/src/stm32/stm32_usbdev.c
@@ -2346,6 +2346,13 @@ static void stm32_suspend(struct stm32_usbdev_s *priv)
{
uint16_t regval;
+ /* Notify the class driver of the suspend event */
+
+ if (priv->driver)
+ {
+ CLASS_SUSPEND(priv->driver, &priv->usbdev);
+ }
+
/* Disable ESOF polling, disable the SUSP interrupt, and enable the WKUP
* interrupt. Clear any pending WKUP interrupt.
*/
@@ -2411,6 +2418,13 @@ static void stm32_initresume(struct stm32_usbdev_s *priv)
/* Reset FSUSP bit and enable normal interrupt handling */
stm32_putreg(STM32_CNTR_SETUP, STM32_USB_CNTR);
+
+ /* Notify the class driver of the resume event */
+
+ if (priv->driver)
+ {
+ CLASS_RESUME(priv->driver, &priv->usbdev);
+ }
}
/****************************************************************************
diff --git a/nuttx/arch/avr/src/at90usb/at90usb_usbdev.c b/nuttx/arch/avr/src/at90usb/at90usb_usbdev.c
index 89949e662..0e3ac6487 100644
--- a/nuttx/arch/avr/src/at90usb/at90usb_usbdev.c
+++ b/nuttx/arch/avr/src/at90usb/at90usb_usbdev.c
@@ -1955,6 +1955,15 @@ static inline void avr_gensuspend(void)
{
usbtrace(TRACE_INTENTRY(AVR_TRACEINTID_SUSPEND), UDIEN);
+ /* Notify the class driver of the suspend event */
+
+ if (g_usbdev.driver)
+ {
+ CLASS_SUSPEND(g_usbdev.driver, &g_usbdev.usbdev);
+ }
+
+ /* Disable suspend event interrupts; enable wakeup event interrupt */
+
UDIEN &= ~(1 << SUSPE);
UDIEN |= (1 << WAKEUPE);
@@ -1992,6 +2001,13 @@ static void avr_genwakeup(void)
USBCON &= ~(1 << FRZCLK);
UDIEN &= ~(1 << WAKEUPE);
UDIEN |= (1 << SUSPE);
+
+ /* Notify the class driver of the resume event */
+
+ if (g_usbdev.driver)
+ {
+ CLASS_RESUME(g_usbdev.driver, &g_usbdev.usbdev);
+ }
}
/*******************************************************************************
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-usbdev.c b/nuttx/arch/mips/src/pic32mx/pic32mx-usbdev.c
index dafd35aa0..8d9f7c058 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-usbdev.c
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-usbdev.c
@@ -2901,6 +2901,13 @@ static void pic32mx_suspend(struct pic32mx_usbdev_s *priv)
{
uint16_t regval;
+ /* Notify the class driver of the suspend event */
+
+ if (priv->driver)
+ {
+ CLASS_SUSPEND(priv->driver, &priv->usbdev);
+ }
+
/* Enable the ACTV interrupt.
*
* NOTE: Do not clear UIRbits.ACTVIF here! Reason: ACTVIF is only
@@ -2977,8 +2984,16 @@ static void pic32mx_resume(struct pic32mx_usbdev_s *priv)
* PLL to lock.
*/
- pic32mx_putreg(USB_INT_IDLE, PIC32MX_USBOTG_IR);
- irqrestore(flags);
+ pic32mx_putreg(USB_INT_IDLE, PIC32MX_USBOTG_IR);
+
+ /* Notify the class driver of the resume event */
+
+ if (priv->driver)
+ {
+ CLASS_RESUME(priv->driver, &priv->usbdev);
+ }
+
+ irqrestore(flags);
}
/****************************************************************************