summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-01-08 21:33:57 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-01-08 21:33:57 +0000
commit0bc978aa032d7bd2a60c577cc261ccdcb8dfd628 (patch)
tree4a16b4b9277f9ddb00b016918c819e991aab8e70 /nuttx
parentf0656284a031663c77d59bd4a7fa3b2857767676 (diff)
downloadpx4-nuttx-0bc978aa032d7bd2a60c577cc261ccdcb8dfd628.tar.gz
px4-nuttx-0bc978aa032d7bd2a60c577cc261ccdcb8dfd628.tar.bz2
px4-nuttx-0bc978aa032d7bd2a60c577cc261ccdcb8dfd628.zip
Replace logic STM32 IDLE loop with standard power management interfaces
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4284 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/src/stm32/Make.defs12
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_idle.c74
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_rcclock.c111
-rw-r--r--nuttx/include/nuttx/pm.h9
4 files changed, 72 insertions, 134 deletions
diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs
index 0d046ebc3..6306f2a26 100644
--- a/nuttx/arch/arm/src/stm32/Make.defs
+++ b/nuttx/arch/arm/src/stm32/Make.defs
@@ -1,7 +1,7 @@
############################################################################
# arch/arm/src/stm32/Make.defs
#
-# 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
@@ -57,14 +57,14 @@ CHIP_CSRCS = stm32_allocateheap.c stm32_start.c stm32_rcc.c stm32_lse.c \
stm32_gpio.c stm32_exti.c stm32_flash.c stm32_irq.c \
stm32_timerisr.c stm32_dma.c stm32_lowputc.c stm32_serial.c \
stm32_spi.c stm32_usbdev.c stm32_sdio.c stm32_tim.c stm32_i2c.c \
- stm32_idle.c stm32_waste.c
+ stm32_waste.c
-ifeq ($(CONFIG_STM32_ETHMAC),y)
-CHIP_CSRCS += stm32_eth.c
+ifneq ($(CONFIG_IDLE_CUSTOM),y)
+CHIP_CSRCS += stm32_idle.c
endif
-ifeq ($(CONFIG_STM32_RCCLOCK),y)
-CHIP_CSRCS += stm32_rcclock.c
+ifeq ($(CONFIG_STM32_ETHMAC),y)
+CHIP_CSRCS += stm32_eth.c
endif
ifeq ($(CONFIG_STM32_PWR),y)
diff --git a/nuttx/arch/arm/src/stm32/stm32_idle.c b/nuttx/arch/arm/src/stm32/stm32_idle.c
index 0919265ff..ec78861c8 100644
--- a/nuttx/arch/arm/src/stm32/stm32_idle.c
+++ b/nuttx/arch/arm/src/stm32/stm32_idle.c
@@ -1,8 +1,8 @@
/****************************************************************************
* arch/arm/src/stm32/stm32_idle.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2011-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
@@ -41,8 +41,11 @@
#include <nuttx/config.h>
#include <nuttx/arch.h>
+#include <nuttx/pm.h>
+
+#include <arch/irq.h>
+
#include "up_internal.h"
-#include "stm32_rcc.h"
/****************************************************************************
* Pre-processor Definitions
@@ -69,6 +72,57 @@
****************************************************************************/
/****************************************************************************
+ * Name: up_idlepm
+ *
+ * Description:
+ * Perform IDLE state power management.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_PM
+static void up_idlepm(void)
+{
+ static enum pm_state_e oldstate = PM_NORMAL;
+ enum pm_state_e newstate;
+ irqstate_t flags;
+ int ret;
+
+ /* Decide, which power saving level can be obtained */
+
+ newstate = pm_checkstate();
+
+ /* Check for state changes */
+
+ if (newstate != oldstate)
+ {
+ flags = irqsave();
+
+ /* Perform board-specific, state-dependent logic here */
+ /* <-- ADD CODE HERE --> */
+
+ /* Then force the global state change */
+
+ ret = pm_changestate(newstate);
+ if (ret < 0)
+ {
+ /* The new state change failed, revert to the preceding state */
+
+ (void)pm_changestate(oldstate);
+ }
+ else
+ {
+ /* Save the new state */
+
+ oldstate = newstate;
+ }
+ irqrestore(flags);
+ }
+}
+#else
+# define up_idlepm()
+#endif
+
+/****************************************************************************
* Public Functions
****************************************************************************/
@@ -95,19 +149,9 @@ void up_idle(void)
sched_process_timer();
#else
-#ifdef CONFIG_STM32_RCCLOCK
+ /* Perform IDLE mode power management */
- /* Decide, which power saving level can be obtained */
-
- if (stm32_getrccactivity())
- {
- /* Sleep mode */
- }
- else
- {
- /* Stop mode */
- }
-#endif
+ up_idlepm();
/* Sleep until an interrupt occurs to save power */
diff --git a/nuttx/arch/arm/src/stm32/stm32_rcclock.c b/nuttx/arch/arm/src/stm32/stm32_rcclock.c
deleted file mode 100644
index 928e34b20..000000000
--- a/nuttx/arch/arm/src/stm32/stm32_rcclock.c
+++ /dev/null
@@ -1,111 +0,0 @@
-/****************************************************************************
- * arch/arm/src/stm32/stm32_rcc.c
- *
- * Copyright (C) 2011 Uros Platise. All rights reserved.
- * Author: Author: Uros Platise <uros.platise@isotel.eu>
- *
- * This file is part of NuttX:
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- *
- * 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 <stdint.h>
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/* Activity reference count, showing inactivity after start-up.
- * Device drivers increment this count using rcclock() and rccunlock()
- *
- * If this value goes beyond the range [0, MAX_RCCs] indicates
- * reference count leakage (asymetric number of locks vs. unlocks) and
- * system enters permanent active state.
- */
-
-static int stm32_rcclock_count = 0;
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-uint32_t stm32_rcclock(uint8_t domain_id)
-{
- // THINK:
- // maybe just shift domain_id into 32-bit or 64-bit register
- // and if there value of this var != 0, we are active...
- // increment some variable, so it is possible to test leakage
- // multiple locks or multiple unlocks
-
- if (stm32_rcclock_count >= 0)
- {
- stm32_rcclock_count++;
- if (stm32_rcclock_count > 64)
- {
- stm32_rcclock_count = -1; /* capture error */
- }
- }
-
- return 0;
-}
-
-uint32_t stm32_rccunlock(uint8_t domain_id)
-{
- if (stm32_rcclock_count > -1)
- {
- stm32_rcclock_count--;
- }
- return 0;
-}
-
-uint32_t stm32_setrccoptions(uint8_t domain_id, uint32_t options)
-{
- return 0;
-}
-
-int stm32_getrccactivity(void)
-{
- return stm32_rcclock_count;
-}
diff --git a/nuttx/include/nuttx/pm.h b/nuttx/include/nuttx/pm.h
index 520348ca6..308960fdb 100644
--- a/nuttx/include/nuttx/pm.h
+++ b/nuttx/include/nuttx/pm.h
@@ -2,8 +2,8 @@
* include/nuttx/pm.h
* NuttX Power Management Interfaces
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2011-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
@@ -78,6 +78,11 @@
* Pre-Processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
+/* CONFIG_IDLE_CUSTOM. Some architectures support this definition. This,
+ * if defined, will allow you replace the default IDLE loop with your
+ * own, custom idle loop to support board-specific IDLE time power managment
+ */
+
/* Time slices. The power management module collects activity counts in
* time slices. At the end of the time slice, the count accumulated during
* that interval is applied to an averaging algorithm to determine the