forked from Archive/PX4-Autopilot
STM32 power management update
git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4848 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
parent
8bbd7a5455
commit
3611ea2855
|
@ -45,6 +45,7 @@
|
||||||
|
|
||||||
#include <arch/irq.h>
|
#include <arch/irq.h>
|
||||||
|
|
||||||
|
#include "stm32_pm.h"
|
||||||
#include "up_internal.h"
|
#include "up_internal.h"
|
||||||
|
|
||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
|
@ -98,7 +99,8 @@ static void up_idlepm(void)
|
||||||
flags = irqsave();
|
flags = irqsave();
|
||||||
|
|
||||||
/* Perform board-specific, state-dependent logic here */
|
/* Perform board-specific, state-dependent logic here */
|
||||||
/* <-- ADD CODE HERE --> */
|
|
||||||
|
llvdbg("newstate= %d oldstate=%d\n", newstate, oldstate);
|
||||||
|
|
||||||
/* Then force the global state change */
|
/* Then force the global state change */
|
||||||
|
|
||||||
|
@ -115,6 +117,29 @@ static void up_idlepm(void)
|
||||||
|
|
||||||
oldstate = newstate;
|
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);
|
irqrestore(flags);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -51,6 +51,7 @@
|
||||||
#include <nuttx/irq.h>
|
#include <nuttx/irq.h>
|
||||||
#include <nuttx/arch.h>
|
#include <nuttx/arch.h>
|
||||||
#include <nuttx/serial/serial.h>
|
#include <nuttx/serial/serial.h>
|
||||||
|
#include <nuttx/power/pm.h>
|
||||||
|
|
||||||
#include <arch/serial.h>
|
#include <arch/serial.h>
|
||||||
#include <arch/board/board.h>
|
#include <arch/board/board.h>
|
||||||
|
@ -129,6 +130,12 @@
|
||||||
# define RXDMA_BUFFER_SIZE 32
|
# define RXDMA_BUFFER_SIZE 32
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/* Power management definitions */
|
||||||
|
|
||||||
|
#if defined(CONFIG_PM) && !defined(CONFG_PM_SERIAL_ACTIVITY)
|
||||||
|
# define CONFG_PM_SERIAL_ACTIVITY 10
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef USE_SERIALDRIVER
|
#ifdef USE_SERIALDRIVER
|
||||||
#ifdef HAVE_UART
|
#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);
|
static void up_dma_rxcallback(DMA_HANDLE handle, uint8_t status, void *arg);
|
||||||
#endif
|
#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
|
#ifdef CONFIG_STM32_USART1
|
||||||
static int up_interrupt_usart1(int irq, void *context);
|
static int up_interrupt_usart1(int irq, void *context);
|
||||||
#endif
|
#endif
|
||||||
|
@ -638,6 +650,14 @@ static struct up_dev_s *uart_devs[STM32_NUSART] =
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#ifdef CONFIG_PM
|
||||||
|
static struct pm_callback_s g_serialcb =
|
||||||
|
{
|
||||||
|
.notify = up_pm_notify,
|
||||||
|
.prepare = up_pm_prepare,
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
* Private Functions
|
* Private Functions
|
||||||
****************************************************************************/
|
****************************************************************************/
|
||||||
|
@ -1067,6 +1087,12 @@ static int up_interrupt_common(struct up_dev_s *priv)
|
||||||
int passes;
|
int passes;
|
||||||
bool handled;
|
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,
|
/* Loop until there are no characters to be transferred or,
|
||||||
* until we have been looping for a long time.
|
* until we have been looping for a long time.
|
||||||
*/
|
*/
|
||||||
|
@ -1535,6 +1561,99 @@ static void up_dma_rxcallback(DMA_HANDLE handle, uint8_t status, void *arg)
|
||||||
|
|
||||||
#endif /* HAVE UART */
|
#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
|
* Public Functions
|
||||||
****************************************************************************/
|
****************************************************************************/
|
||||||
|
@ -1586,6 +1705,16 @@ void up_serialinit(void)
|
||||||
#ifdef HAVE_UART
|
#ifdef HAVE_UART
|
||||||
char devname[16];
|
char devname[16];
|
||||||
unsigned i, j;
|
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 */
|
/* Register the console */
|
||||||
|
|
||||||
|
|
|
@ -68,6 +68,7 @@
|
||||||
#include <nuttx/lcd/lcd.h>
|
#include <nuttx/lcd/lcd.h>
|
||||||
|
|
||||||
#include <arch/board/board.h>
|
#include <arch/board/board.h>
|
||||||
|
#include <nuttx/power/pm.h>
|
||||||
|
|
||||||
#include "up_arch.h"
|
#include "up_arch.h"
|
||||||
#include "stm32.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_getcontrast(struct lcd_dev_s *dev);
|
||||||
static int stm3210e_setcontrast(struct lcd_dev_s *dev, unsigned int contrast);
|
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 */
|
/* Initialization */
|
||||||
|
|
||||||
static inline void stm3210e_lcdinitialize(void);
|
static inline void stm3210e_lcdinitialize(void);
|
||||||
|
@ -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
|
* Private Functions
|
||||||
**************************************************************************************/
|
**************************************************************************************/
|
||||||
|
@ -1022,8 +1039,7 @@ static int stm3210e_setpower(struct lcd_dev_s *dev, int power)
|
||||||
|
|
||||||
if (power > 0)
|
if (power > 0)
|
||||||
{
|
{
|
||||||
#ifdef CONFIG_LCD_BACKLIGHT
|
#if defined(CONFIG_LCD_BACKLIGHT) && defined(CONFIG_LCD_PWM)
|
||||||
#ifdef CONFIG_LCD_PWM
|
|
||||||
uint32_t frac;
|
uint32_t frac;
|
||||||
uint32_t duty;
|
uint32_t duty;
|
||||||
|
|
||||||
|
@ -1052,12 +1068,12 @@ static int stm3210e_setpower(struct lcd_dev_s *dev, int power)
|
||||||
{
|
{
|
||||||
duty--;
|
duty--;
|
||||||
}
|
}
|
||||||
|
|
||||||
putreg16((uint16_t)duty, STM32_TIM1_CCR1);
|
putreg16((uint16_t)duty, STM32_TIM1_CCR1);
|
||||||
#else
|
#else
|
||||||
/* Turn the backlight on */
|
/* Turn the backlight on */
|
||||||
|
|
||||||
stm32_gpiowrite(GPIO_LCD_BACKLIGHT, true);
|
stm32_gpiowrite(GPIO_LCD_BACKLIGHT, true);
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
/* Then turn the display on */
|
/* Then turn the display on */
|
||||||
|
|
||||||
|
@ -1110,6 +1126,133 @@ static int stm3210e_setcontrast(struct lcd_dev_s *dev, unsigned int contrast)
|
||||||
return -ENOSYS;
|
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
|
* Name: stm3210e_lcdinitialize
|
||||||
*
|
*
|
||||||
|
@ -1309,6 +1452,8 @@ static inline void stm3210e_lcdinitialize(void)
|
||||||
#endif
|
#endif
|
||||||
{
|
{
|
||||||
#ifndef CONFIG_STM32_AM240320_DISABLE
|
#ifndef CONFIG_STM32_AM240320_DISABLE
|
||||||
|
/* Set the LCD type for the AM240320 */
|
||||||
|
|
||||||
g_lcddev.type = LCD_TYPE_AM240320;
|
g_lcddev.type = LCD_TYPE_AM240320;
|
||||||
lcddbg("LCD type: %d\n", g_lcddev.type);
|
lcddbg("LCD type: %d\n", g_lcddev.type);
|
||||||
|
|
||||||
|
@ -1586,8 +1731,22 @@ static void stm3210e_backlight(void)
|
||||||
|
|
||||||
int up_lcdinitialize(void)
|
int up_lcdinitialize(void)
|
||||||
{
|
{
|
||||||
|
#ifdef CONFIG_PM
|
||||||
|
int ret;
|
||||||
|
#endif
|
||||||
|
|
||||||
gvdbg("Initializing\n");
|
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 */
|
/* Configure GPIO pins and configure the FSMC to support the LCD */
|
||||||
|
|
||||||
stm32_selectlcd();
|
stm32_selectlcd();
|
||||||
|
|
|
@ -80,7 +80,7 @@
|
||||||
*
|
*
|
||||||
* Description:
|
* Description:
|
||||||
* This function is called by a device driver to indicate that it is
|
* 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
|
* count and/or will restart a idle timer and prevent entering reduced
|
||||||
* power states.
|
* power states.
|
||||||
*
|
*
|
||||||
|
|
|
@ -103,7 +103,7 @@ struct pm_global_s
|
||||||
* pm_changestate()
|
* pm_changestate()
|
||||||
* recommended - The recommended state based on the PM algorithm in
|
* recommended - The recommended state based on the PM algorithm in
|
||||||
* function pm_update().
|
* 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
|
* mcnt - A tiny counter used only at start up. The actual
|
||||||
* algorithm cannot be applied until CONFIG_PM_MEMORY
|
* algorithm cannot be applied until CONFIG_PM_MEMORY
|
||||||
* samples have been collected.
|
* samples have been collected.
|
||||||
|
|
|
@ -307,10 +307,12 @@ struct pm_callback_s
|
||||||
* Returned Value:
|
* Returned Value:
|
||||||
* None. The driver already agreed to transition to the low power
|
* None. The driver already agreed to transition to the low power
|
||||||
* consumption state when when it returned OK to the prepare() call.
|
* 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);
|
||||||
};
|
};
|
||||||
|
|
||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
|
|
Loading…
Reference in New Issue