summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-06-18 14:45:34 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-06-18 14:45:34 +0000
commitbfd033e8d48306e431481ba6d43fa36f2125f785 (patch)
tree14f0f20818529c9779cfebbf76828dc19231aac8 /nuttx
parent9c8afa0fd9e51de419fca55a158e01953839d68f (diff)
downloadpx4-nuttx-bfd033e8d48306e431481ba6d43fa36f2125f785.tar.gz
px4-nuttx-bfd033e8d48306e431481ba6d43fa36f2125f785.tar.bz2
px4-nuttx-bfd033e8d48306e431481ba6d43fa36f2125f785.zip
STM32 power management update
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4848 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_idle.c27
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_serial.c149
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_lcd.c205
-rw-r--r--nuttx/drivers/power/pm_activity.c2
-rw-r--r--nuttx/drivers/power/pm_internal.h2
-rw-r--r--nuttx/include/nuttx/power/pm.h4
6 files changed, 352 insertions, 37 deletions
diff --git a/nuttx/arch/arm/src/stm32/stm32_idle.c b/nuttx/arch/arm/src/stm32/stm32_idle.c
index b5fd9fcb3..791a79429 100644
--- a/nuttx/arch/arm/src/stm32/stm32_idle.c
+++ b/nuttx/arch/arm/src/stm32/stm32_idle.c
@@ -45,6 +45,7 @@
#include <arch/irq.h>
+#include "stm32_pm.h"
#include "up_internal.h"
/****************************************************************************
@@ -98,7 +99,8 @@ static void up_idlepm(void)
flags = irqsave();
/* Perform board-specific, state-dependent logic here */
- /* <-- ADD CODE HERE --> */
+
+ llvdbg("newstate= %d oldstate=%d\n", newstate, oldstate);
/* Then force the global state change */
@@ -115,6 +117,29 @@ static void up_idlepm(void)
oldstate = newstate;
}
+
+ /* MCU-specific power management logic */
+
+ switch (newstate)
+ {
+ case PM_NORMAL:
+ break;
+
+ case PM_IDLE:
+ break;
+
+ case PM_STANDBY:
+ stm32_pmstop(true);
+ break;
+
+ case PM_SLEEP:
+ (void)stm32_pmstandby();
+ break;
+
+ default:
+ break;
+ }
+
irqrestore(flags);
}
}
diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c
index b9682eae4..ab456eeb5 100644
--- a/nuttx/arch/arm/src/stm32/stm32_serial.c
+++ b/nuttx/arch/arm/src/stm32/stm32_serial.c
@@ -51,6 +51,7 @@
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include <nuttx/serial/serial.h>
+#include <nuttx/power/pm.h>
#include <arch/serial.h>
#include <arch/board/board.h>
@@ -120,7 +121,7 @@
# error "USART6 DMA channel not defined (DMAMAP_USART6_RX)"
# endif
-/* The DMA buffer size when using RX DMA to emulate a FIFO.
+/* The DMA buffer size when using RX DMA to emulate a FIFO.
*
* When streaming data, the generic serial layer will be called
* everytime the FIFO receives half this number of bytes.
@@ -129,6 +130,12 @@
# define RXDMA_BUFFER_SIZE 32
#endif
+/* Power management definitions */
+
+#if defined(CONFIG_PM) && !defined(CONFG_PM_SERIAL_ACTIVITY)
+# define CONFG_PM_SERIAL_ACTIVITY 10
+#endif
+
#ifdef USE_SERIALDRIVER
#ifdef HAVE_UART
@@ -199,6 +206,11 @@ static bool up_dma_rxavailable(struct uart_dev_s *dev);
static void up_dma_rxcallback(DMA_HANDLE handle, uint8_t status, void *arg);
#endif
+#ifdef CONFIG_PM
+static void up_pm_notify(struct pm_callback_s *cb, enum pm_state_e pmstate);
+static int up_pm_prepare(struct pm_callback_s *cb, enum pm_state_e pmstate);
+#endif
+
#ifdef CONFIG_STM32_USART1
static int up_interrupt_usart1(int irq, void *context);
#endif
@@ -638,6 +650,14 @@ static struct up_dev_s *uart_devs[STM32_NUSART] =
#endif
};
+#ifdef CONFIG_PM
+static struct pm_callback_s g_serialcb =
+{
+ .notify = up_pm_notify,
+ .prepare = up_pm_prepare,
+};
+#endif
+
/****************************************************************************
* Private Functions
****************************************************************************/
@@ -914,15 +934,15 @@ static int up_dma_setup(struct uart_dev_s *dev)
priv->usartbase + STM32_USART_DR_OFFSET,
(uint32_t)priv->rxfifo,
RXDMA_BUFFER_SIZE,
- DMA_SCR_DIR_P2M |
- DMA_SCR_CIRC |
- DMA_SCR_MINC |
- DMA_SCR_PSIZE_8BITS |
+ DMA_SCR_DIR_P2M |
+ DMA_SCR_CIRC |
+ DMA_SCR_MINC |
+ DMA_SCR_PSIZE_8BITS |
DMA_SCR_MSIZE_8BITS |
DMA_SCR_PBURST_SINGLE |
DMA_SCR_MBURST_SINGLE);
- /* Reset our DMA shadow pointer to match the address just
+ /* Reset our DMA shadow pointer to match the address just
* programmed above.
*/
@@ -1067,6 +1087,12 @@ static int up_interrupt_common(struct up_dev_s *priv)
int passes;
bool handled;
+ /* Report serial activity to the power management logic */
+
+#if defined(CONFIG_PM) && CONFG_PM_SERIAL_ACTIVITY > 0
+ pm_activity(CONFG_PM_SERIAL_ACTIVITY);
+#endif
+
/* Loop until there are no characters to be transferred or,
* until we have been looping for a long time.
*/
@@ -1380,7 +1406,7 @@ static bool up_dma_rxavailable(struct uart_dev_s *dev)
{
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
- /* Compare our receive pointer to the current DMA pointer, if they
+ /* Compare our receive pointer to the current DMA pointer, if they
* do not match, then there are bytes to be received.
*/
@@ -1423,7 +1449,7 @@ static void up_txint(struct uart_dev_s *dev, bool enable)
* USART_CR1_TXEIE 7 USART_SR_TXE Transmit Data Register Empty
* USART_CR3_CTSIE 10 USART_SR_CTS CTS flag (not used)
*/
-
+
flags = irqsave();
if (enable)
{
@@ -1536,6 +1562,99 @@ static void up_dma_rxcallback(DMA_HANDLE handle, uint8_t status, void *arg)
#endif /* HAVE UART */
/****************************************************************************
+ * Name: up_pm_notify
+ *
+ * Description:
+ * Notify the driver of new power state. This callback is called after
+ * all drivers have had the opportunity to prepare for the new power state.
+ *
+ * Input Parameters:
+ *
+ * cb - Returned to the driver. The driver version of the callback
+ * strucure may include additional, driver-specific state data at
+ * the end of the structure.
+ *
+ * pmstate - Identifies the new PM state
+ *
+ * Returned Value:
+ * None - The driver already agreed to transition to the low power
+ * consumption state when when it returned OK to the prepare() call.
+ *
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_PM
+static void up_pm_notify(struct pm_callback_s *cb, enum pm_state_e pmstate)
+{
+ switch (pmstate)
+ {
+ case(PM_NORMAL):
+ /* Logic for PM_NORMAL goes here */
+ break;
+
+ case(PM_IDLE):
+ /* Logic for PM_IDLE goes here */
+ break;
+
+ case(PM_STANDBY):
+ /* Logic for PM_STANDBY goes here */
+ break;
+
+ case(PM_SLEEP):
+ /* Logic for PM_SLEEP goes here */
+ break;
+
+ default:
+ /* Should not get here */
+ break;
+ }
+}
+#endif
+
+/****************************************************************************
+ * Name: up_pm_prepare
+ *
+ * Description:
+ * Request the driver to prepare for a new power state. This is a warning
+ * that the system is about to enter into a new power state. The driver
+ * should begin whatever operations that may be required to enter power
+ * state. The driver may abort the state change mode by returning a
+ * non-zero value from the callback function.
+ *
+ * Input Parameters:
+ *
+ * cb - Returned to the driver. The driver version of the callback
+ * strucure may include additional, driver-specific state data at
+ * the end of the structure.
+ *
+ * pmstate - Identifies the new PM state
+ *
+ * Returned Value:
+ * Zero - (OK) means the event was successfully processed and that the
+ * driver is prepared for the PM state change.
+ *
+ * Non-zero - means that the driver is not prepared to perform the tasks
+ * needed achieve this power setting and will cause the state
+ * change to be aborted. NOTE: The prepare() method will also
+ * be called when reverting from lower back to higher power
+ * consumption modes (say because another driver refused a
+ * lower power state change). Drivers are not permitted to
+ * return non-zero values when reverting back to higher power
+ * consumption modes!
+ *
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_PM
+static int up_pm_prepare(struct pm_callback_s *cb, enum pm_state_e pmstate)
+{
+ /* Logic to prepare for a reduced power state goes here. */
+
+ return OK;
+}
+#endif
+
+/****************************************************************************
* Public Functions
****************************************************************************/
@@ -1556,7 +1675,7 @@ void up_earlyserialinit(void)
/* Disable all USART interrupts */
- for (i = 0; i < STM32_NUSART; i++)
+ for (i = 0; i < STM32_NUSART; i++)
{
if (uart_devs[i])
{
@@ -1586,6 +1705,16 @@ void up_serialinit(void)
#ifdef HAVE_UART
char devname[16];
unsigned i, j;
+#ifdef CONFIG_PM
+ int ret;
+#endif
+
+ /* Register to receive power management callbacks */
+
+#ifdef CONFIG_PM
+ ret = pm_register(&g_serialcb);
+ DEBUGASSERT(ret == OK);
+#endif
/* Register the console */
@@ -1598,7 +1727,7 @@ void up_serialinit(void)
strcpy(devname, "/dev/ttySx");
- for (i = 0, j = 1; i < STM32_NUSART; i++)
+ for (i = 0, j = 1; i < STM32_NUSART; i++)
{
/* don't create a device for the console - we did that above */
diff --git a/nuttx/configs/stm3210e-eval/src/up_lcd.c b/nuttx/configs/stm3210e-eval/src/up_lcd.c
index 11da916d1..d6e4a613d 100644
--- a/nuttx/configs/stm3210e-eval/src/up_lcd.c
+++ b/nuttx/configs/stm3210e-eval/src/up_lcd.c
@@ -49,7 +49,7 @@
* Omitting the above (or setting them to "n") enables support for the LCD. Setting
* any of the above to "y" will disable support for the corresponding LCD.
*/
-
+
/**************************************************************************************
* Included Files
**************************************************************************************/
@@ -68,6 +68,7 @@
#include <nuttx/lcd/lcd.h>
#include <arch/board/board.h>
+#include <nuttx/power/pm.h>
#include "up_arch.h"
#include "stm32.h"
@@ -403,6 +404,13 @@ static int stm3210e_setpower(struct lcd_dev_s *dev, int power);
static int stm3210e_getcontrast(struct lcd_dev_s *dev);
static int stm3210e_setcontrast(struct lcd_dev_s *dev, unsigned int contrast);
+/* LCD Power Management */
+
+#ifdef CONFIG_PM
+static void stm3210e_pm_notify(struct pm_callback_s *cb, enum pm_state_e pmstate);
+static int stm3210e_pm_prepare(struct pm_callback_s *cb, enum pm_state_e pmstate);
+#endif
+
/* Initialization */
static inline void stm3210e_lcdinitialize(void);
@@ -441,7 +449,7 @@ static const struct fb_videoinfo_s g_videoinfo =
/* This is the standard, NuttX Plane information object */
-static const struct lcd_planeinfo_s g_planeinfo =
+static const struct lcd_planeinfo_s g_planeinfo =
{
.putrun = stm3210e_putrun, /* Put a run into LCD memory */
.getrun = stm3210e_getrun, /* Get a run from LCD memory */
@@ -451,12 +459,12 @@ static const struct lcd_planeinfo_s g_planeinfo =
/* This is the standard, NuttX LCD driver object */
-static struct stm3210e_dev_s g_lcddev =
+static struct stm3210e_dev_s g_lcddev =
{
.dev =
{
/* LCD Configuration */
-
+
.getvideoinfo = stm3210e_getvideoinfo,
.getplaneinfo = stm3210e_getplaneinfo,
@@ -472,6 +480,15 @@ static struct stm3210e_dev_s g_lcddev =
},
};
+#ifdef CONFIG_PM
+static struct pm_callback_s g_lcdcb =
+{
+ .notify = stm3210e_pm_notify,
+ .prepare = stm3210e_pm_prepare,
+};
+#endif
+
+
/**************************************************************************************
* Private Functions
**************************************************************************************/
@@ -580,7 +597,7 @@ static void stm3210e_readnosetup(FAR uint16_t *accum)
* Red and green appear to be swapped on read-back as well
* - R61580: There is a 16-bit (1 pixel) shift in the returned data.
* All colors in the normal order
- * - AM240320: Unknown -- assuming colors are in the color order
+ * - AM240320: Unknown -- assuming colors are in the color order
*
**************************************************************************************/
@@ -716,7 +733,7 @@ static int stm3210e_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *bu
{
FAR const uint16_t *src = (FAR const uint16_t*)buffer;
int i;
-
+
/* Buffer must be provided and aligned to a 16-bit address boundary */
lcddbg("row: %d col: %d npixels: %d\n", row, col, npixels);
@@ -768,7 +785,7 @@ static int stm3210e_putrun(fb_coord_t row, fb_coord_t col, FAR const uint8_t *bu
col = (STM3210E_XRES-1) - col;
row = (STM3210E_YRES-1) - row;
-
+
/* Then write the GRAM data, manually incrementing Y (which is col) */
for (i = 0; i < npixels; i++)
@@ -809,7 +826,7 @@ static int stm3210e_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
uint16_t (*readgram)(FAR uint16_t *accum);
uint16_t accum;
int i;
-
+
/* Buffer must be provided and aligned to a 16-bit address boundary */
lcddbg("row: %d col: %d npixels: %d\n", row, col, npixels);
@@ -843,7 +860,7 @@ static int stm3210e_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
default: /* Shouldn't happen */
return -ENOSYS;
}
-
+
/* Read the run from GRAM. */
#ifdef CONFIG_LCD_LANDSCAPE
@@ -896,7 +913,7 @@ static int stm3210e_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer,
col = (STM3210E_XRES-1) - col;
row = (STM3210E_YRES-1) - row;
-
+
/* Then write the GRAM data, manually incrementing Y (which is col) */
for (i = 0; i < npixels; i++)
@@ -980,7 +997,7 @@ static int stm3210e_poweroff(void)
{
/* Turn the display off */
- stm3210e_writereg(LCD_REG_7, 0);
+ stm3210e_writereg(LCD_REG_7, 0);
/* Disable timer 1 clocking */
@@ -1022,8 +1039,7 @@ static int stm3210e_setpower(struct lcd_dev_s *dev, int power)
if (power > 0)
{
-#ifdef CONFIG_LCD_BACKLIGHT
-#ifdef CONFIG_LCD_PWM
+#if defined(CONFIG_LCD_BACKLIGHT) && defined(CONFIG_LCD_PWM)
uint32_t frac;
uint32_t duty;
@@ -1052,13 +1068,13 @@ static int stm3210e_setpower(struct lcd_dev_s *dev, int power)
{
duty--;
}
+
putreg16((uint16_t)duty, STM32_TIM1_CCR1);
#else
/* Turn the backlight on */
stm32_gpiowrite(GPIO_LCD_BACKLIGHT, true);
#endif
-#endif
/* Then turn the display on */
#ifndef CONFIG_STM32_AM240320_DISABLE
@@ -1110,6 +1126,133 @@ static int stm3210e_setcontrast(struct lcd_dev_s *dev, unsigned int contrast)
return -ENOSYS;
}
+/****************************************************************************
+ * Name: stm3210e_pm_notify
+ *
+ * Description:
+ * Notify the driver of new power state. This callback is called after
+ * all drivers have had the opportunity to prepare for the new power state.
+ *
+ * Input Parameters:
+ *
+ * cb - Returned to the driver. The driver version of the callback
+ * strucure may include additional, driver-specific state data at
+ * the end of the structure.
+ *
+ * pmstate - Identifies the new PM state
+ *
+ * Returned Value:
+ * None - The driver already agreed to transition to the low power
+ * consumption state when when it returned OK to the prepare() call.
+ *
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_PM
+static void stm3210e_pm_notify(struct pm_callback_s *cb , enum pm_state_e pmstate)
+{
+#ifdef CONFIG_LCD_PWM
+ uint32_t frac;
+ uint32_t duty;
+#endif
+
+ switch (pmstate)
+ {
+ case(PM_NORMAL):
+ {
+ /* Restore normal LCD operation */
+
+#ifdef CONFIG_LCD_PWM
+ frac = (g_lcddev.power << 16) / CONFIG_LCD_MAXPOWER;
+ duty = (g_lcddev.reload * frac) >> 16;
+ if (duty > 0)
+ {
+ duty--;
+ }
+ putreg16((uint16_t)duty, STM32_TIM1_CCR1);
+#endif
+ }
+ break;
+
+ case(PM_IDLE):
+ {
+ /* Entering IDLE mode - Turn display off */
+
+#ifdef CONFIG_LCD_PWM
+ lldbg("power:%d \n", g_lcddev.power);
+ putreg16(0, STM32_TIM1_CCR1);
+#endif
+ }
+ break;
+
+ case(PM_STANDBY):
+ {
+ /* Entering STANDBY mode - Logic for PM_STANDBY goes here */
+ }
+ break;
+
+ case(PM_SLEEP):
+ {
+ /* Entering SLEEP mode - Logic for PM_SLEEP goes here */
+
+ }
+ break;
+
+ default:
+ {
+ /* Should not get here */
+
+ }
+ break;
+ }
+}
+#endif
+
+/****************************************************************************
+ * Name: stm3210e_pm_prepare
+ *
+ * Description:
+ * Request the driver to prepare for a new power state. This is a warning
+ * that the system is about to enter into a new power state. The driver
+ * should begin whatever operations that may be required to enter power
+ * state. The driver may abort the state change mode by returning a
+ * non-zero value from the callback function.
+ *
+ * Input Parameters:
+ *
+ * cb - Returned to the driver. The driver version of the callback
+ * strucure may include additional, driver-specific state data at
+ * the end of the structure.
+ *
+ * pmstate - Identifies the new PM state
+ *
+ * Returned Value:
+ * Zero - (OK) means the event was successfully processed and that the
+ * driver is prepared for the PM state change.
+ *
+ * Non-zero - means that the driver is not prepared to perform the tasks
+ * needed achieve this power setting and will cause the state
+ * change to be aborted. NOTE: The prepare() method will also
+ * be called when reverting from lower back to higher power
+ * consumption modes (say because another driver refused a
+ * lower power state change). Drivers are not permitted to
+ * return non-zero values when reverting back to higher power
+ * consumption modes!
+ *
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_PM
+static int stm3210e_pm_prepare(struct pm_callback_s *cb , enum pm_state_e pmstate)
+{
+ /* No preparation to change power modes is required by the LCD driver. We always
+ * accept the state change by returning OK.
+ */
+
+ return OK;
+}
+#endif
+
/**************************************************************************************
* Name: stm3210e_lcdinitialize
*
@@ -1216,13 +1359,13 @@ static inline void stm3210e_lcdinitialize(void)
/* Panel Control */
- stm3210e_writereg(LCD_REG_144, 0x0010);
+ stm3210e_writereg(LCD_REG_144, 0x0010);
stm3210e_writereg(LCD_REG_146, 0x0000);
stm3210e_writereg(LCD_REG_147, 0x0003);
stm3210e_writereg(LCD_REG_149, 0x0110);
stm3210e_writereg(LCD_REG_151, 0x0000);
stm3210e_writereg(LCD_REG_152, 0x0000);
-
+
/* Set GRAM write direction and BGR=1
* I/D=01 (Horizontal : increment, Vertical : decrement)
* AM=1 (address is updated in vertical writing direction)
@@ -1309,6 +1452,8 @@ static inline void stm3210e_lcdinitialize(void)
#endif
{
#ifndef CONFIG_STM32_AM240320_DISABLE
+ /* Set the LCD type for the AM240320 */
+
g_lcddev.type = LCD_TYPE_AM240320;
lcddbg("LCD type: %d\n", g_lcddev.type);
@@ -1361,7 +1506,7 @@ static inline void stm3210e_lcdinitialize(void)
stm3210e_writereg(LCD_REG_57, 0x0007);
stm3210e_writereg(LCD_REG_60, 0x0600);
stm3210e_writereg(LCD_REG_61, 0x020b);
-
+
/* Set GRAM area */
stm3210e_writereg(LCD_REG_80, 0x0000); /* Horizontal GRAM Start Address */
@@ -1451,9 +1596,9 @@ static void stm3210e_backlight(void)
{
reload = 65535;
}
-
+
g_lcddev.reload = reload;
-
+
/* Configure PA8 as TIM1 CH1 output */
stm32_configgpio(GPIO_TIM1_CH1OUT);
@@ -1507,7 +1652,7 @@ static void stm3210e_backlight(void)
cr2 = getreg16(STM32_TIM1_CR2);
/* Select the Output Compare Mode Bits */
-
+
ccmr = getreg16(STM32_TIM1_CCMR1);
ccmr &= ATIM_CCMR1_OC1M_MASK;
ccmr |= (ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC1M_SHIFT);
@@ -1586,8 +1731,22 @@ static void stm3210e_backlight(void)
int up_lcdinitialize(void)
{
+#ifdef CONFIG_PM
+ int ret;
+#endif
+
gvdbg("Initializing\n");
+ /* Register to receive power management callbacks */
+
+#ifdef CONFIG_PM
+ ret = pm_register(&g_lcdcb);
+ if (ret =! OK)
+ {
+ lcddbg("ERROR: pm_register failed: %d\n", ret);
+ }
+#endif
+
/* Configure GPIO pins and configure the FSMC to support the LCD */
stm32_selectlcd();
@@ -1650,12 +1809,12 @@ void up_lcduninitialize(void)
void stm3210e_lcdclear(uint16_t color)
{
uint32_t i = 0;
-
- stm3210e_setcursor(0, STM3210E_XRES-1);
+
+ stm3210e_setcursor(0, STM3210E_XRES-1);
stm3210e_gramselect();
for (i = 0; i < STM3210E_XRES * STM3210E_YRES; i++)
{
LCD->value = color;
- }
+ }
}
diff --git a/nuttx/drivers/power/pm_activity.c b/nuttx/drivers/power/pm_activity.c
index 8cef46684..f52fc93ff 100644
--- a/nuttx/drivers/power/pm_activity.c
+++ b/nuttx/drivers/power/pm_activity.c
@@ -80,7 +80,7 @@
*
* Description:
* This function is called by a device driver to indicate that it is
- * performing meaningful activities (non-idle). This increment an activty
+ * performing meaningful activities (non-idle). This increments an activity
* count and/or will restart a idle timer and prevent entering reduced
* power states.
*
diff --git a/nuttx/drivers/power/pm_internal.h b/nuttx/drivers/power/pm_internal.h
index 0ae4722da..f98624f15 100644
--- a/nuttx/drivers/power/pm_internal.h
+++ b/nuttx/drivers/power/pm_internal.h
@@ -103,7 +103,7 @@ struct pm_global_s
* pm_changestate()
* recommended - The recommended state based on the PM algorithm in
* function pm_update().
- * mndex - The index to the next slot in the memory[] arry to use.
+ * mndex - The index to the next slot in the memory[] array to use.
* mcnt - A tiny counter used only at start up. The actual
* algorithm cannot be applied until CONFIG_PM_MEMORY
* samples have been collected.
diff --git a/nuttx/include/nuttx/power/pm.h b/nuttx/include/nuttx/power/pm.h
index c75f5e691..86e23f090 100644
--- a/nuttx/include/nuttx/power/pm.h
+++ b/nuttx/include/nuttx/power/pm.h
@@ -307,10 +307,12 @@ struct pm_callback_s
* Returned Value:
* None. The driver already agreed to transition to the low power
* consumption state when when it returned OK to the prepare() call.
+ * At that time it should have made all preprations necessary to enter
+ * the new state. Now the driver must make the state transition.
*
**************************************************************************/
- int (*notify)(FAR struct pm_callback_s *cb, enum pm_state_e pmstate);
+ void (*notify)(FAR struct pm_callback_s *cb, enum pm_state_e pmstate);
};
/****************************************************************************