Skip to content

Commit

Permalink
I2C low power updates
Browse files Browse the repository at this point in the history
-Add timeout for staying in RUN mode after waking up or receiving I2C transaction
-Prevent entering sleep if I2C command is being processed
-Update power source when usb is attached/detached
-Don't process I2C Writes with nop cmd
  • Loading branch information
gerargz authored and gaborcsapo committed Jun 29, 2022
1 parent e25c017 commit 218b6ae
Show file tree
Hide file tree
Showing 4 changed files with 39 additions and 22 deletions.
2 changes: 1 addition & 1 deletion source/board/microbitv2/IO_Config_Override.h
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ COMPILER_ASSERT(DAPLINK_HIC_ID == DAPLINK_HIC_ID_KL27Z);
#define PIN_WAKE_ON_EDGE (1<<PIN_WAKE_ON_EDGE_BIT)
#define PIN_WAKE_ON_EDGE_LLWU_PIN (8)
#define PIN_WAKE_ON_EDGE_LLWU_WAKEUP_TYPE kLLWU_ExternalPinFallingEdge
#define PIN_WAKE_ON_EDGE_PORT_WAKEUP_TYPE kPORT_InterruptFallingEdge
#define PIN_WAKE_ON_EDGE_PORT_WAKEUP_TYPE kPORT_InterruptEitherEdge

// Power LEDs

Expand Down
16 changes: 13 additions & 3 deletions source/board/microbitv2/i2c.c
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,9 @@ static i2cReadCallback_t pfReadCommsCallback = NULL;
static i2cWriteCallback_t pfWriteFlashCallback = NULL;
static i2cReadCallback_t pfReadFlashCallback = NULL;

extern uint8_t i2c_wake_timeout;
extern bool i2c_allow_sleep;

static void i2c_slave_callback(I2C_Type *base, i2c_slave_transfer_t *xfer, void *userData) {
switch (xfer->event)
{
Expand All @@ -37,6 +40,7 @@ static void i2c_slave_callback(I2C_Type *base, i2c_slave_transfer_t *xfer, void
xfer->dataSize = 0;
// fsl_i2c.c IRQ updated in fsl_i2c_mod.c to include I2C D register
address_match = *(uint8_t*)userData >> 1;
i2c_wake_timeout = 3; // 3 * 30ms tick = 90ms timeout
break;
/* Transmit request */
case kI2C_SlaveTransmitEvent:
Expand Down Expand Up @@ -67,16 +71,21 @@ static void i2c_slave_callback(I2C_Type *base, i2c_slave_transfer_t *xfer, void

// Default driver couldn't differentiate between RX or TX completion
// Check flag set in kI2C_SlaveReceiveEvent

main_board_event();

// Ignore NOP cmd in I2C Write
if (!(g_SlaveRxFlag && g_slave_RX_buff[0] == 0x00)) {
main_board_event();
}

i2c_allow_sleep = false;
break;

default:
g_SlaveCompletionFlag = false;
break;
}
}

// Hook function executed in the main task
void board_custom_event() {

if (g_SlaveRxFlag) {
Expand All @@ -94,6 +103,7 @@ void board_custom_event() {
pfReadFlashCallback(&g_slave_TX_buff[0], transferredCount);
}
}
i2c_allow_sleep = true;
}

static void i2c_init_pins(void) {
Expand Down
23 changes: 13 additions & 10 deletions source/board/microbitv2/microbitv2.c
Original file line number Diff line number Diff line change
Expand Up @@ -250,21 +250,24 @@ void board_30ms_hook()
main_shutdown_state = MAIN_SHUTDOWN_REQUESTED;
}

if (prev_usb_state != usb_state) {
power_source = pwr_mon_get_power_source();
if (wake_from_usb) {
main_shutdown_state = MAIN_USER_EVENT;

if (usb_state == USB_DISCONNECTED) {
usb_state = USB_CONNECTING;
}
}

if (i2c_wake_timeout > 0) {
i2c_wake_timeout--;
}
prev_usb_state = usb_state;

// Enter light sleep if USB is not enumerated and main_shutdown_state is idle
if (usb_state == USB_DISCONNECTED && !usb_pc_connected && main_shutdown_state == MAIN_SHUTDOWN_WAITING
&& automatic_sleep_on == true && g_s_handle.isBusy == false) {
&& automatic_sleep_on == true && g_s_handle.isBusy == false && i2c_wake_timeout == 0 && i2c_allow_sleep) {
interface_power_mode = kAPP_PowerModeVlps;
main_shutdown_state = MAIN_SHUTDOWN_REQUESTED;
}

if (wake_from_usb) {
main_shutdown_state = MAIN_SHUTDOWN_ALERT;
}

switch (main_shutdown_state) {
case MAIN_LED_FULL_BRIGHTNESS:
Expand Down Expand Up @@ -319,7 +322,7 @@ void board_30ms_hook()
main_shutdown_state = MAIN_SHUTDOWN_WAITING;
}
break;
case MAIN_SHUTDOWN_ALERT:
case MAIN_USER_EVENT:
{
// Release COMBINED_SENSOR_INT in case it was previously asserted
PORT_SetPinMux(COMBINED_SENSOR_INT_PORT, COMBINED_SENSOR_INT_PIN, kPORT_PinDisabledOrAnalog);
Expand Down Expand Up @@ -758,7 +761,7 @@ static void i2c_write_comms_callback(uint8_t* pData, uint8_t size) {
break;
default:
i2cResponse.cmdId = gErrorResponse_c;
i2cResponse.cmdData.errorRspCmd.errorCode = gErrorUnknownProperty_c;
i2cResponse.cmdData.errorRspCmd.errorCode = gErrorUnknownCommand_c;
break;
}

Expand Down
20 changes: 12 additions & 8 deletions source/board/microbitv2/power.c
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,10 @@

#include "main.h"
#include "power.h"
#include "pwr_mon.h"
#include "IO_Config.h"
#include "uart.h"
#include "i2c.h"
#include "rl_usb.h"

/*******************************************************************************
Expand All @@ -28,6 +30,7 @@ extern volatile uint8_t wake_from_reset;
extern volatile uint8_t wake_from_usb;
extern volatile bool usb_pc_connected;
extern main_usb_connect_t usb_state;
extern power_source_t power_source;

/*******************************************************************************
* Code
Expand Down Expand Up @@ -59,8 +62,12 @@ void PORTCD_IRQHandler(void)
if ((1U << PIN_WAKE_ON_EDGE_BIT) & PORT_GetPinsInterruptFlags(PIN_WAKE_ON_EDGE_PORT))
{
PORT_ClearPinsInterruptFlags(PIN_WAKE_ON_EDGE_PORT, (1U << PIN_WAKE_ON_EDGE_BIT));

power_source = pwr_mon_get_power_source();

if ((PIN_WAKE_ON_EDGE_PORT->PCR[PIN_WAKE_ON_EDGE_BIT] & PORT_PCR_IRQC_MASK) == PORT_PCR_IRQC(kPORT_InterruptRisingEdge)) {
bool usb_on = (((PIN_WAKE_ON_EDGE_GPIO->PDIR) >> PIN_WAKE_ON_EDGE_BIT) & 0x01U) ? false : true;

if (usb_on == false) {
/* Reset USB on cable detach (VBUS falling edge) */
USBD_Reset();
usbd_reset_core();
Expand Down Expand Up @@ -91,8 +98,8 @@ void power_init(void)
/* Disable USB voltage regulator */
SIM->SOPT1 &= ~SIM_SOPT1_USBREGEN_MASK;

/* Enable rising edge interrupt on WAKE_ON_EDGE pin (VBUS falling edge) to detect USB detach */
PORT_SetPinInterruptConfig(PIN_WAKE_ON_EDGE_PORT, PIN_WAKE_ON_EDGE_BIT, kPORT_InterruptRisingEdge);
/* Enable either edge interrupt on WAKE_ON_EDGE pin to detect USB attach/detach */
PORT_SetPinInterruptConfig(PIN_WAKE_ON_EDGE_PORT, PIN_WAKE_ON_EDGE_BIT, PIN_WAKE_ON_EDGE_PORT_WAKEUP_TYPE);

NVIC_SetPriority(LLWU_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL);
NVIC_EnableIRQ(LLWU_IRQn);
Expand Down Expand Up @@ -128,7 +135,6 @@ static void power_enter_mode(app_power_mode_t targetPowerMode)
static void power_set_wakeup_config(app_power_mode_t targetMode)
{
PORT_SetPinInterruptConfig(PIN_SW_RESET_PORT, PIN_SW_RESET_BIT, PIN_SW_RESET_PORT_WAKEUP_TYPE);
PORT_SetPinInterruptConfig(PIN_WAKE_ON_EDGE_PORT, PIN_WAKE_ON_EDGE_BIT, PIN_WAKE_ON_EDGE_PORT_WAKEUP_TYPE);

/* If targetMode is VLLS/LLS, setup LLWU. */
if ((kAPP_PowerModeWait != targetMode) && (kAPP_PowerModeVlpw != targetMode) &&
Expand Down Expand Up @@ -197,7 +203,6 @@ static void power_pre_switch_hook(smc_power_state_t originPowerState, app_power_

static void power_post_switch_hook(smc_power_state_t originPowerState, app_power_mode_t targetMode)
{

/* Configure I/O pin SWCLK */
PIN_SWCLK_PORT->PCR[PIN_SWCLK_BIT] = PORT_PCR_MUX(1) | /* GPIO */
PORT_PCR_PE_MASK; /* Pull (Down) enable */
Expand All @@ -213,7 +218,6 @@ static void power_post_switch_hook(smc_power_state_t originPowerState, app_power
PORT_SetPinMux(UART_PORT, PIN_UART_TX_BIT, (port_mux_t)PIN_UART_TX_MUX_ALT);

uart_initialize();

/* Change to rising edge interrupt on WAKE_ON_EDGE pin (VBUS falling edge) to detect USB detach */
PORT_SetPinInterruptConfig(PIN_WAKE_ON_EDGE_PORT, PIN_WAKE_ON_EDGE_BIT, kPORT_InterruptRisingEdge);
i2c_deinitialize();
i2c_initialize();
}

0 comments on commit 218b6ae

Please sign in to comment.