summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog2
-rw-r--r--nuttx/TODO11
-rw-r--r--nuttx/arch/arm/src/armv7-m/nvic.h9
-rw-r--r--nuttx/arch/arm/src/common/up_initialize.c10
-rw-r--r--nuttx/arch/arm/src/common/up_internal.h8
-rw-r--r--nuttx/arch/arm/src/stm32/Make.defs4
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_pwr.h2
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_pm.h137
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_pminitialize.c107
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_pmstandby.c116
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_pmstop.c121
-rw-r--r--nuttx/configs/pic32-starterkit/nsh/defconfig4
-rw-r--r--nuttx/configs/pic32-starterkit/nsh2/defconfig4
-rw-r--r--nuttx/configs/pic32-starterkit/ostest/defconfig4
-rw-r--r--nuttx/include/nuttx/power/pm.h10
15 files changed, 533 insertions, 16 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index bd20c19dd..f7b5b81b3 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -2571,3 +2571,5 @@
NSH command ifconfig over Telnet. In that case the function netdev_foreach
takes the network device semaphore, but so does the telnet logic causing
the deadlock.
+ * arch/arm/src/stm32/stm32_pm*.c: Add basic STM32 power management logic
+ that will eventually be used to implement low power states.
diff --git a/nuttx/TODO b/nuttx/TODO
index 0b0ba9dfd..8993edd6c 100644
--- a/nuttx/TODO
+++ b/nuttx/TODO
@@ -1256,11 +1256,14 @@ o 8051 / MCS51 (arch/8051/)
o MIPS (arch/mips)
^^^^^^^^^^^^^^^^
- Title: PIC32MX USB DRIVER UNTESTED
- Description: A USB device-side driver has been written for the PIC3MX,
- is completely untested as of this writing.
+ Title: PIC32MX USB MASS STORAGE
+ Description: A USB device-side driver has been written for the PIC3MX and
+ is partially tested. It does not, however, seem to work with the
+ mass storage device. This is probably due to errors in how endpoint
+ stalls are handled since the mass storage protocol depends on stalls
+ to indicate the end-of-data.
Status: Open
- Priority: Low -- unless you need a USB device-side driver.
+ Priority: Medium
o Hitachi/Renesas SH-1 (arch/sh/src/sh1)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
diff --git a/nuttx/arch/arm/src/armv7-m/nvic.h b/nuttx/arch/arm/src/armv7-m/nvic.h
index 07d9cde6f..de34cc7b9 100644
--- a/nuttx/arch/arm/src/armv7-m/nvic.h
+++ b/nuttx/arch/arm/src/armv7-m/nvic.h
@@ -433,6 +433,15 @@
#define NVIC_INTCTRL_VECTACTIVE_SHIFT 0 /* Bits 8-0: Active ISR number */
#define NVIC_INTCTRL_VECTACTIVE_MASK (0x1ff << NVIC_INTCTRL_VECTACTIVE_SHIFT)
+/* System control register (SYSCON) */
+
+ /* Bit 0: Reserved */
+#define NVIC_SYSCON_SLEEPONEXIT (1 << 1) /* Bit 1: Sleep-on-exit (returning from Handler to Thread mode) */
+#define NVIC_SYSCON_SLEEPDEEP (1 << 2) /* Bit 2: Use deep sleep in low power mode */
+ /* Bit 3: Reserved */
+#define NVIC_SYSCON_SEVONPEND (1 << 4) /* Bit 4: Send Event on Pending bit */
+ /* Bits 5-31: Reserved */
+
/* System handler 4-7 priority register */
#define NVIC_SYSH_PRIORITY_PR4_SHIFT 0
diff --git a/nuttx/arch/arm/src/common/up_initialize.c b/nuttx/arch/arm/src/common/up_initialize.c
index 130f0721f..8bf530fda 100644
--- a/nuttx/arch/arm/src/common/up_initialize.c
+++ b/nuttx/arch/arm/src/common/up_initialize.c
@@ -126,6 +126,16 @@ void up_initialize(void)
up_irqinitialize();
+ /* Initialize the power management subsystem. This MCU-specific function
+ * must be called *very* early in the intialization sequence *before* any
+ * other device drivers are initialized (since they may attempt to register
+ * with the power management subsystem).
+ */
+
+#ifdef CONFIG_PM
+ up_pminitialize();
+#endif
+
/* Initialize the DMA subsystem if the weak function stm32_dmainitialize has been
* brought into the build
*/
diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h
index f0f3d06ef..015b2b4bc 100644
--- a/nuttx/arch/arm/src/common/up_internal.h
+++ b/nuttx/arch/arm/src/common/up_internal.h
@@ -229,6 +229,14 @@ extern void up_switchcontext(uint32_t *saveregs, uint32_t *restoreregs);
extern void up_sigdeliver(void);
+/* Power management *********************************************************/
+
+#ifdef CONFIG_PM
+extern void up_pminitialize(void);
+#else
+# define up_pminitialize()
+#endif
+
/* Interrupt handling *******************************************************/
extern void up_irqinitialize(void);
diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs
index 351680685..79f0979cc 100644
--- a/nuttx/arch/arm/src/stm32/Make.defs
+++ b/nuttx/arch/arm/src/stm32/Make.defs
@@ -76,6 +76,10 @@ ifneq ($(CONFIG_IDLE_CUSTOM),y)
CHIP_CSRCS += stm32_idle.c
endif
+ifeq ($(CONFIG_PM),y)
+CHIP_CSRCS += stm32_pminitialize.c stm32_pmstop.c stm32_pmstandby.c
+endif
+
ifeq ($(CONFIG_STM32_ETHMAC),y)
CHIP_CSRCS += stm32_eth.c
endif
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_pwr.h b/nuttx/arch/arm/src/stm32/chip/stm32_pwr.h
index 11a6fb1eb..2ece6a357 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_pwr.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_pwr.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/stm32/chip/stm32_pwr.h
*
- * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/arch/arm/src/stm32/stm32_pm.h b/nuttx/arch/arm/src/stm32/stm32_pm.h
new file mode 100644
index 000000000..87af09cb9
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32_pm.h
@@ -0,0 +1,137 @@
+/************************************************************************************
+ * arch/arm/src/stm32/stm32_pm.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_STM32_STM32_PM_H
+#define __ARCH_ARM_SRC_STM32_STM32_PM_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <semaphore.h>
+
+#include "chip.h"
+#include "up_internal.h"
+
+#ifdef CONFIG_PM
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+ #ifndef __ASSEMBLY__
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/* Before any power state transition is made, the caller should hold this
+ * semaphore to assure that there are no concurrent, contradictory power
+ * state activities.
+ */
+
+EXTERN sem_t g_pmsem;
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_pmstop
+ *
+ * Description:
+ * Enter STOP mode.
+ *
+ * Input Parameters:
+ * lpds - true: To further reduce power consumption in Stop mode, put the
+ * internal voltage regulator in low-power mode using the LPDS bit
+ * of the Power control register (PWR_CR).
+ *
+ * Returned Value:
+ * Zero means that the STOP was successfully entered and the system has
+ * been re-awakened. The internal volatage regulator is back to its
+ * original state. Otherwise, STOP mode did not occur and a negated
+ * errno value is returned to indicate the cause of the failure.
+ *
+ * Assumptions:
+ * The caller holds the PM semaphore (g_pmsem).
+ *
+ ****************************************************************************/
+
+EXTERN int stm32_pmstop(bool lpds);
+
+/****************************************************************************
+ * Name: stm32_pmstandby
+ *
+ * Description:
+ * Enter STANDBY mode.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value.
+ * On success, this function will not return (STANDBY mode can only be
+ * terminated with a reset event). Otherwise, STANDBY mode did not occur
+ * and a negated errno value is returned to indicate the cause of the
+ * failure.
+ *
+ * Assumptions:
+ * The caller holds the PM semaphore (g_pmsem).
+ *
+ ****************************************************************************/
+
+EXTERN int stm32_pmstandby(void);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+#endif /* __ASSEMBLY__ */
+
+#endif /* CONFIG_PM */
+#endif /* __ARCH_ARM_SRC_STM32_STM32_PM_H */
diff --git a/nuttx/arch/arm/src/stm32/stm32_pminitialize.c b/nuttx/arch/arm/src/stm32/stm32_pminitialize.c
new file mode 100644
index 000000000..f065cdfc8
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32_pminitialize.c
@@ -0,0 +1,107 @@
+/****************************************************************************
+ * arch/arm/src/stm32/stm32_pminitialize.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <nuttx/power/pm.h>
+
+#include "up_internal.h"
+#include "stm32_pm.h"
+
+#ifdef CONFIG_PM
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* Before any power state transition is made, the caller should hold this
+ * semaphore to assure that there are no concurrent, contradictory power
+ * state activities.
+ */
+
+sem_t g_pmsem;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_pminitialize
+ *
+ * Description:
+ * This function is called by MCU-specific logic at power-on reset in
+ * order to provide one-time initialization the power management subystem.
+ * This function must be called *very* early in the intialization sequence
+ * *before* any other device drivers are initialized (since they may
+ * attempt to register with the power management subsystem).
+ *
+ * Input parameters:
+ * None.
+ *
+ * Returned value:
+ * None.
+ *
+ ****************************************************************************/
+
+void up_pminitialize(void)
+{
+ /* Initialize the PM semaphore to assure that no more than one power-related
+ * action occurs at a time.
+ */
+
+ sem_init(&g_pmsem, 0, 1);
+
+ /* Then initialize the NuttX power management subsystem proper */
+
+ pm_initialize();
+}
+
+#endif /* CONFIG_PM */
diff --git a/nuttx/arch/arm/src/stm32/stm32_pmstandby.c b/nuttx/arch/arm/src/stm32/stm32_pmstandby.c
new file mode 100644
index 000000000..7364dbaeb
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32_pmstandby.c
@@ -0,0 +1,116 @@
+/****************************************************************************
+ * arch/arm/src/stm32/stm32_pmstandby.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+
+#include "up_arch.h"
+#include "nvic.h"
+#include "stm32_pwr.h"
+#include "stm32_pm.h"
+
+#ifdef CONFIG_PM
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_pmstandby
+ *
+ * Description:
+ * Enter STANDBY mode.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value.
+ * On success, this function will not return (STANDBY mode can only be
+ * terminated with a reset event). Otherwise, STANDBY mode did not occur
+ * and a negated errno value is returned to indicate the cause of the
+ * failure.
+ *
+ * Assumptions:
+ * The caller holds the PM semaphore (g_pmsem).
+ *
+ ****************************************************************************/
+
+int stm32_pmstandby(void)
+{
+ uint32_t regval;
+
+ /* Clear the Wake-Up Flag by setting the CWUF bit in the power control
+ * register.
+ */
+
+ regval = getreg32(STM32_PWR_CR);
+ regval |= PWR_CR_CWUF;
+ putreg32(regval, STM32_PWR_CR);
+
+ /* Set the Power Down Deep Sleep (PDDS) bit in the power control register. */
+
+ regval |= PWR_CR_PDDS;
+ putreg32(regval, STM32_PWR_CR);
+
+ /* Set SLEEPDEEP bit of Cortex System Control Register */
+
+ regval = getreg32(NVIC_SYSCON);
+ regval |= NVIC_SYSCON_SLEEPDEEP;
+ putreg32(regval, NVIC_SYSCON);
+
+ /* Sleep until the wakeup reset occurs */
+
+ asm("WFI");
+ return OK; /* Won't get here */
+}
+
+#endif /* CONFIG_PM */
diff --git a/nuttx/arch/arm/src/stm32/stm32_pmstop.c b/nuttx/arch/arm/src/stm32/stm32_pmstop.c
new file mode 100644
index 000000000..259f0d7df
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32_pmstop.c
@@ -0,0 +1,121 @@
+/****************************************************************************
+ * arch/arm/src/stm32/stm32_pmstop.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+
+#include "up_arch.h"
+#include "nvic.h"
+#include "stm32_pwr.h"
+#include "stm32_pm.h"
+
+#ifdef CONFIG_PM
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_pmstop
+ *
+ * Description:
+ * Enter STOP mode.
+ *
+ * Input Parameters:
+ * lpds - true: To further reduce power consumption in Stop mode, put the
+ * internal voltage regulator in low-power mode using the LPDS bit
+ * of the Power control register (PWR_CR).
+ *
+ * Returned Value:
+ * Zero means that the STOP was successfully entered and the system has
+ * been re-awakened. The internal volatage regulator is back to its
+ * original state. Otherwise, STOP mode did not occur and a negated
+ * errno value is returned to indicate the cause of the failure.
+ *
+ * Assumptions:
+ * The caller holds the PM semaphore (g_pmsem).
+ *
+ ****************************************************************************/
+
+int stm32_pmstop(bool lpds)
+{
+ uint32_t regval;
+
+ /* Clear the Power Down Deep Sleep (PDDS) and the Low Power Deep Sleep
+ * (LPDS)) bits in the power control register.
+ */
+
+ regval = getreg32(STM32_PWR_CR);
+ regval &= ~(PWR_CR_LPDS | PWR_CR_PDDS);
+
+ /* Set the Low Power Deep Sleep (LPDS) bit if so requested */
+
+ if (lpds)
+ {
+ regval |= PWR_CR_LPDS;
+ }
+
+ putreg32(regval, STM32_PWR_CR);
+
+ /* Set SLEEPDEEP bit of Cortex System Control Register */
+
+ regval = getreg32(NVIC_SYSCON);
+ regval |= NVIC_SYSCON_SLEEPDEEP;
+ putreg32(regval, NVIC_SYSCON);
+
+ /* Sleep until the wakeup interrupt occurs (us WFE to wait for an event) */
+
+ asm("WFI");
+ return OK;
+}
+
+#endif /* CONFIG_PM */
diff --git a/nuttx/configs/pic32-starterkit/nsh/defconfig b/nuttx/configs/pic32-starterkit/nsh/defconfig
index 9dcdf6a37..6746fc3b5 100644
--- a/nuttx/configs/pic32-starterkit/nsh/defconfig
+++ b/nuttx/configs/pic32-starterkit/nsh/defconfig
@@ -305,8 +305,8 @@ CONFIG_PHY_LAN8720=n
CONFIG_PHY_AUTONEG=y
CONFIG_PHY_SPEED100=n
CONFIG_PHY_FDUPLEX=y
-CONFIG_NET_NTXDESC=7
-CONFIG_NET_NRXDESC=7
+CONFIG_NET_NTXDESC=3
+CONFIG_NET_NRXDESC=5
CONFIG_NET_REGDEBUG=n
CONFIG_NET_DESCDEBUG=n
CONFIG_NET_DUMPPACKET=n
diff --git a/nuttx/configs/pic32-starterkit/nsh2/defconfig b/nuttx/configs/pic32-starterkit/nsh2/defconfig
index f5bff6ffa..342a7d349 100644
--- a/nuttx/configs/pic32-starterkit/nsh2/defconfig
+++ b/nuttx/configs/pic32-starterkit/nsh2/defconfig
@@ -305,8 +305,8 @@ CONFIG_PHY_LAN8720=n
CONFIG_PHY_AUTONEG=y
CONFIG_PHY_SPEED100=n
CONFIG_PHY_FDUPLEX=y
-CONFIG_NET_NTXDESC=7
-CONFIG_NET_NRXDESC=7
+CONFIG_NET_NTXDESC=3
+CONFIG_NET_NRXDESC=5
CONFIG_NET_REGDEBUG=n
CONFIG_NET_DESCDEBUG=n
CONFIG_NET_DUMPPACKET=n
diff --git a/nuttx/configs/pic32-starterkit/ostest/defconfig b/nuttx/configs/pic32-starterkit/ostest/defconfig
index ec433ec4e..19a8376c2 100644
--- a/nuttx/configs/pic32-starterkit/ostest/defconfig
+++ b/nuttx/configs/pic32-starterkit/ostest/defconfig
@@ -305,8 +305,8 @@ CONFIG_PHY_LAN8720=n
CONFIG_PHY_AUTONEG=y
CONFIG_PHY_SPEED100=n
CONFIG_PHY_FDUPLEX=y
-CONFIG_NET_NTXDESC=7
-CONFIG_NET_NRXDESC=7
+CONFIG_NET_NTXDESC=3
+CONFIG_NET_NRXDESC=5
CONFIG_NET_REGDEBUG=n
CONFIG_NET_DESCDEBUG=n
CONFIG_NET_DUMPPACKET=n
diff --git a/nuttx/include/nuttx/power/pm.h b/nuttx/include/nuttx/power/pm.h
index 7c9433c22..3ee0b9d09 100644
--- a/nuttx/include/nuttx/power/pm.h
+++ b/nuttx/include/nuttx/power/pm.h
@@ -333,11 +333,11 @@ extern "C" {
* Name: pm_initialize
*
* Description:
- * This function is called by MCU-specific one-time at power on reset in
- * order to initialize the power management capabilities. This function
- * must be called *very* early in the intialization sequence *before* any
- * other device drivers are initialize (since they may attempt to register
- * with the power management subsystem).
+ * This function is called by MCU-specific logic at power-on reset in
+ * order to provide one-time initialization the power management subystem.
+ * This function must be called *very* early in the intialization sequence
+ * *before* any other device drivers are initialized (since they may
+ * attempt to register with the power management subsystem).
*
* Input parameters:
* None.