Improve power consumption and SLEEP mode :

- Disable IDLE hook (it would wake the device up as soon as possible).
 - Logger task sleep for 100ms (disable logging for better battery life)
 - Logging is disabled by default
 - Apply fix for ERRATA 87 (clear FPU interrupt before going to sleep). Ports files from FreeRTOS are now in the sources (they where in the SDK before)
This commit is contained in:
JF 2020-01-05 11:09:07 +01:00
parent 7688f46898
commit bbe4e500c3
11 changed files with 1047 additions and 21 deletions

View File

@ -131,9 +131,6 @@ macro(nRF5x_setup)
${NRF5_SDK_PATH}/external/freertos/source/event_groups.c
${NRF5_SDK_PATH}/external/freertos/source/portable/MemMang/heap_1.c
${NRF5_SDK_PATH}/external/freertos/source/list.c
${NRF5_SDK_PATH}/external/freertos/portable/GCC/nrf52/port.c
${NRF5_SDK_PATH}/external/freertos/portable/CMSIS/nrf52/port_cmsis.c
${NRF5_SDK_PATH}/external/freertos/portable/CMSIS/nrf52/port_cmsis_systick.c
${NRF5_SDK_PATH}/external/freertos/source/queue.c
${NRF5_SDK_PATH}/external/freertos/source/stream_buffer.c
${NRF5_SDK_PATH}/external/freertos/source/tasks.c
@ -144,8 +141,6 @@ macro(nRF5x_setup)
# freertos include
include_directories(
${NRF5_SDK_PATH}/external/freertos/source/include
${NRF5_SDK_PATH}/external/freertos/portable/CMSIS/nrf52
${NRF5_SDK_PATH}/external/freertos/portable/GCC/nrf52
)
# toolchain specific

View File

@ -42,6 +42,9 @@ list(APPEND SOURCE_FILES
Components/Ble/BleController.cpp
Components/DateTime/DateTimeController.cpp
drivers/Cst816s.cpp
FreeRTOS/port.c
FreeRTOS/port_cmsis_systick.c
FreeRTOS/port_cmsis.c
)
set(INCLUDE_FILES
@ -59,6 +62,12 @@ set(INCLUDE_FILES
Components/Ble/BleController.h
Components/DateTime/DateTimeController.h
drivers/Cst816s.h
FreeRTOS/portmacro.h
FreeRTOS/portmacro_cmsis.h
)
include_directories(
FreeRTOS/
)
nRF5x_addExecutable(pinetime-app "${SOURCE_FILES}")

148
src/FreeRTOS/port.c Normal file
View File

@ -0,0 +1,148 @@
/*
* FreeRTOS Kernel V10.0.0
* Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software. If you wish to use our Amazon
* FreeRTOS name, please do so in a fair use way that does not cause confusion.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
* http://www.FreeRTOS.org
* http://aws.amazon.com/freertos
*
* 1 tab == 4 spaces!
*/
/*-----------------------------------------------------------
* Implementation of functions defined in portable.h for the ARM CM4F port.
*----------------------------------------------------------*/
/* Scheduler includes. */
#include "FreeRTOS.h"
#include "task.h"
/*
* Start first task is a separate function so it can be tested in isolation.
*/
void vPortStartFirstTask( void ) __attribute__ (( naked ));
/*
* Exception handlers.
*/
void vPortSVCHandler( void ) __attribute__ (( naked ));
void xPortPendSVHandler( void ) __attribute__ (( naked ));
/*-----------------------------------------------------------*/
void vPortStartFirstTask( void )
{
__asm volatile(
#if defined(__SES_ARM)
" ldr r0, =_vectors \n" /* Locate the stack using _vectors table. */
#else
" ldr r0, =__isr_vector \n" /* Locate the stack using __isr_vector table. */
#endif
" ldr r0, [r0] \n"
" msr msp, r0 \n" /* Set the msp back to the start of the stack. */
" cpsie i \n" /* Globally enable interrupts. */
" cpsie f \n"
" dsb \n"
" isb \n"
#ifdef SOFTDEVICE_PRESENT
/* Block kernel interrupts only (PendSV) before calling SVC */
" mov r0, %0 \n"
" msr basepri, r0 \n"
#endif
" svc 0 \n" /* System call to start first task. */
" \n"
" .align 2 \n"
#ifdef SOFTDEVICE_PRESENT
::"i"(configKERNEL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS))
#endif
);
}
/*-----------------------------------------------------------*/
void vPortSVCHandler( void )
{
__asm volatile (
" ldr r3, =pxCurrentTCB \n" /* Restore the context. */
" ldr r1, [r3] \n" /* Use pxCurrentTCBConst to get the pxCurrentTCB address. */
" ldr r0, [r1] \n" /* The first item in pxCurrentTCB is the task top of stack. */
" ldmia r0!, {r4-r11, r14} \n" /* Pop the registers that are not automatically saved on exception entry and the critical nesting count. */
" msr psp, r0 \n" /* Restore the task stack pointer. */
" isb \n"
" mov r0, #0 \n"
" msr basepri, r0 \n"
" bx r14 \n"
" \n"
" .align 2 \n"
);
}
/*-----------------------------------------------------------*/
void xPortPendSVHandler( void )
{
/* This is a naked function. */
__asm volatile
(
" mrs r0, psp \n"
" isb \n"
" \n"
" ldr r3, =pxCurrentTCB \n" /* Get the location of the current TCB. */
" ldr r2, [r3] \n"
" \n"
" tst r14, #0x10 \n" /* Is the task using the FPU context? If so, push high vfp registers. */
" it eq \n"
" vstmdbeq r0!, {s16-s31} \n"
" \n"
" stmdb r0!, {r4-r11, r14} \n" /* Save the core registers. */
" \n"
" str r0, [r2] \n" /* Save the new top of stack into the first member of the TCB. */
" \n"
" stmdb sp!, {r3} \n"
" mov r0, %0 \n"
" msr basepri, r0 \n"
" dsb \n"
" isb \n"
" bl vTaskSwitchContext \n"
" mov r0, #0 \n"
" msr basepri, r0 \n"
" ldmia sp!, {r3} \n"
" \n"
" ldr r1, [r3] \n" /* The first item in pxCurrentTCB is the task top of stack. */
" ldr r0, [r1] \n"
" \n"
" ldmia r0!, {r4-r11, r14} \n" /* Pop the core registers. */
" \n"
" tst r14, #0x10 \n" /* Is the task using the FPU context? If so, pop the high vfp registers too. */
" it eq \n"
" vldmiaeq r0!, {s16-s31} \n"
" \n"
" msr psp, r0 \n"
" isb \n"
" \n"
" \n"
" bx r14 \n"
" \n"
" .align 2 \n"
::"i"(configMAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS))
);
}

357
src/FreeRTOS/port_cmsis.c Normal file
View File

@ -0,0 +1,357 @@
/*
* FreeRTOS Kernel V10.0.0
* Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software. If you wish to use our Amazon
* FreeRTOS name, please do so in a fair use way that does not cause confusion.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
* http://www.FreeRTOS.org
* http://aws.amazon.com/freertos
*
* 1 tab == 4 spaces!
*/
/*-----------------------------------------------------------
* Implementation of functions defined in portable.h for the ARM CM4F port.
*----------------------------------------------------------*/
/* Scheduler includes. */
#include "FreeRTOS.h"
#include "task.h"
#ifdef SOFTDEVICE_PRESENT
#include "nrf_soc.h"
#include "app_util.h"
#include "app_util_platform.h"
#endif
#if !(__FPU_USED) && !(__LINT__)
#error This port can only be used when the project options are configured to enable hardware floating point support.
#endif
#if configMAX_SYSCALL_INTERRUPT_PRIORITY == 0
#error configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to 0. See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html
#endif
/* Constants used to detect a Cortex-M7 r0p1 core, which should use the ARM_CM7
r0p1 port. */
#define portCORTEX_M4_r0p1_ID ( 0x410FC241UL )
/* Constants required to check the validity of an interrupt priority. */
#define portFIRST_USER_INTERRUPT_NUMBER ( 16 )
#define portMAX_8_BIT_VALUE ( ( uint8_t ) 0xff )
#define portTOP_BIT_OF_BYTE ( ( uint8_t ) 0x80 )
/* Constants required to set up the initial stack. */
#define portINITIAL_XPSR (((xPSR_Type){.b.T = 1}).w)
#define portINITIAL_EXEC_RETURN ( 0xfffffffd )
/* Let the user override the pre-loading of the initial LR with the address of
prvTaskExitError() in case is messes up unwinding of the stack in the
debugger. */
#ifdef configTASK_RETURN_ADDRESS
#define portTASK_RETURN_ADDRESS configTASK_RETURN_ADDRESS
#else
#define portTASK_RETURN_ADDRESS prvTaskExitError
#endif
/* Each task maintains its own interrupt status in the critical nesting
variable. */
static UBaseType_t uxCriticalNesting = 0;
/*
* Setup the timer to generate the tick interrupts. The implementation in this
* file is weak to allow application writers to change the timer used to
* generate the tick interrupt.
*/
extern void vPortSetupTimerInterrupt( void );
/*
* Exception handlers.
*/
void xPortSysTickHandler( void );
/*
* Start first task is a separate function so it can be tested in isolation.
*/
extern void vPortStartFirstTask( void );
/*
* Function to enable the VFP.
*/
static void vPortEnableVFP( void );
/*
* Used to catch tasks that attempt to return from their implementing function.
*/
static void prvTaskExitError( void );
/*-----------------------------------------------------------*/
/*
* Used by the portASSERT_IF_INTERRUPT_PRIORITY_INVALID() macro to ensure
* FreeRTOS API functions are not called from interrupts that have been assigned
* a priority above configMAX_SYSCALL_INTERRUPT_PRIORITY.
*/
#if ( configASSERT_DEFINED == 1 )
static uint8_t ucMaxSysCallPriority = 0;
static uint32_t ulMaxPRIGROUPValue = 0;
#endif /* configASSERT_DEFINED */
/*-----------------------------------------------------------*/
/*
* See header file for description.
*/
StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters )
{
/* Simulate the stack frame as it would be created by a context switch
interrupt. */
/* Offset added to account for the way the MCU uses the stack on entry/exit
of interrupts, and to ensure alignment. */
pxTopOfStack--;
*pxTopOfStack = portINITIAL_XPSR; /* xPSR */
pxTopOfStack--;
*pxTopOfStack = ( StackType_t ) pxCode; /* PC */
pxTopOfStack--;
*pxTopOfStack = ( StackType_t ) portTASK_RETURN_ADDRESS; /* LR */
/* Save code space by skipping register initialisation. */
pxTopOfStack -= 5; /* R12, R3, R2 and R1. */
*pxTopOfStack = ( StackType_t ) pvParameters; /* R0 */
/* A save method is being used that requires each task to maintain its
own exec return value. */
pxTopOfStack--;
*pxTopOfStack = portINITIAL_EXEC_RETURN;
pxTopOfStack -= 8; /* R11, R10, R9, R8, R7, R6, R5 and R4. */
return pxTopOfStack;
}
/*-----------------------------------------------------------*/
static void prvTaskExitError( void )
{
/* A function that implements a task must not exit or attempt to return to
its caller as there is nothing to return to. If a task wants to exit it
should instead call vTaskDelete( NULL ).
Artificially force an assert() to be triggered if configASSERT() is
defined, then stop here so application writers can catch the error. */
configASSERT( uxCriticalNesting == ~0UL );
portDISABLE_INTERRUPTS();
for ( ;; );
}
/*-----------------------------------------------------------*/
/*
* See header file for description.
*/
BaseType_t xPortStartScheduler( void )
{
/* configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to 0.
See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html */
configASSERT( configMAX_SYSCALL_INTERRUPT_PRIORITY );
/* This port is designed for nRF52, this is Cortex-M4 r0p1. */
configASSERT( SCB->CPUID == portCORTEX_M4_r0p1_ID );
#if ( configASSERT_DEFINED == 1 )
{
volatile uint32_t ulOriginalPriority;
volatile uint8_t * const pucFirstUserPriorityRegister = &NVIC->IP[0];
volatile uint8_t ucMaxPriorityValue;
/* Determine the maximum priority from which ISR safe FreeRTOS API
functions can be called. ISR safe functions are those that end in
"FromISR". FreeRTOS maintains separate thread and ISR API functions to
ensure interrupt entry is as fast and simple as possible.
Save the interrupt priority value that is about to be clobbered. */
ulOriginalPriority = *pucFirstUserPriorityRegister;
/* Determine the number of priority bits available. First write to all
possible bits. */
*pucFirstUserPriorityRegister = portMAX_8_BIT_VALUE;
/* Read the value back to see how many bits stuck. */
ucMaxPriorityValue = *pucFirstUserPriorityRegister;
/* Use the same mask on the maximum system call priority. */
ucMaxSysCallPriority = configMAX_SYSCALL_INTERRUPT_PRIORITY & ucMaxPriorityValue;
/* Calculate the maximum acceptable priority group value for the number
of bits read back. */
ulMaxPRIGROUPValue = SCB_AIRCR_PRIGROUP_Msk >> SCB_AIRCR_PRIGROUP_Pos;
while ( ( ucMaxPriorityValue & portTOP_BIT_OF_BYTE ) == portTOP_BIT_OF_BYTE )
{
ulMaxPRIGROUPValue--;
ucMaxPriorityValue <<= ( uint8_t ) 0x01;
}
/* Remove any bits that are more than actually existing. */
ulMaxPRIGROUPValue &= SCB_AIRCR_PRIGROUP_Msk >> SCB_AIRCR_PRIGROUP_Pos;
/* Restore the clobbered interrupt priority register to its original
value. */
*pucFirstUserPriorityRegister = ulOriginalPriority;
}
#endif /* conifgASSERT_DEFINED */
/* Make PendSV the lowest priority interrupts. */
NVIC_SetPriority(PendSV_IRQn, configKERNEL_INTERRUPT_PRIORITY);
/* Start the timer that generates the tick ISR. Interrupts are disabled
here already. */
vPortSetupTimerInterrupt();
/* Initialise the critical nesting count ready for the first task. */
uxCriticalNesting = 0;
/* Ensure the VFP is enabled - it should be anyway. */
vPortEnableVFP();
/* Lazy save always. */
FPU->FPCCR |= FPU_FPCCR_ASPEN_Msk | FPU_FPCCR_LSPEN_Msk;
/* Finally this port requires SEVONPEND to be active */
SCB->SCR |= SCB_SCR_SEVONPEND_Msk;
/* Start the first task. */
vPortStartFirstTask();
/* Should never get here as the tasks will now be executing! Call the task
exit error function to prevent compiler warnings about a static function
not being called in the case that the application writer overrides this
functionality by defining configTASK_RETURN_ADDRESS. */
prvTaskExitError();
/* Should not get here! */
return 0;
}
/*-----------------------------------------------------------*/
void vPortEndScheduler( void )
{
/* Not implemented in ports where there is nothing to return to.
Artificially force an assert. */
configASSERT( uxCriticalNesting == 1000UL );
}
/*-----------------------------------------------------------*/
void vPortEnterCritical( void )
{
portDISABLE_INTERRUPTS();
uxCriticalNesting++;
/* This is not the interrupt safe version of the enter critical function so
assert() if it is being called from an interrupt context. Only API
functions that end in "FromISR" can be used in an interrupt. Only assert if
the critical nesting count is 1 to protect against recursive calls if the
assert function also uses a critical section. */
if ( uxCriticalNesting == 1 )
{
configASSERT( ( SCB->ICSR & SCB_ICSR_VECTACTIVE_Msk ) == 0 );
}
}
/*-----------------------------------------------------------*/
void vPortExitCritical( void )
{
configASSERT( uxCriticalNesting );
uxCriticalNesting--;
if ( uxCriticalNesting == 0 )
{
portENABLE_INTERRUPTS();
}
}
/*-----------------------------------------------------------*/
/* This is a naked function. */
static void vPortEnableVFP( void )
{
SCB->CPACR |= 0xf << 20;
}
/*-----------------------------------------------------------*/
#if ( configASSERT_DEFINED == 1 )
void vPortValidateInterruptPriority( void )
{
uint32_t ulCurrentInterrupt;
uint8_t ucCurrentPriority;
IPSR_Type ipsr;
/* Obtain the number of the currently executing interrupt. */
ipsr.w = __get_IPSR();
ulCurrentInterrupt = ipsr.b.ISR;
/* Is the interrupt number a user defined interrupt? */
if ( ulCurrentInterrupt >= portFIRST_USER_INTERRUPT_NUMBER )
{
/* Look up the interrupt's priority. */
ucCurrentPriority = NVIC->IP[ ulCurrentInterrupt - portFIRST_USER_INTERRUPT_NUMBER ];
/* The following assertion will fail if a service routine (ISR) for
an interrupt that has been assigned a priority above
configMAX_SYSCALL_INTERRUPT_PRIORITY calls an ISR safe FreeRTOS API
function. ISR safe FreeRTOS API functions must *only* be called
from interrupts that have been assigned a priority at or below
configMAX_SYSCALL_INTERRUPT_PRIORITY.
Numerically low interrupt priority numbers represent logically high
interrupt priorities, therefore the priority of the interrupt must
be set to a value equal to or numerically *higher* than
configMAX_SYSCALL_INTERRUPT_PRIORITY.
Interrupts that use the FreeRTOS API must not be left at their
default priority of zero as that is the highest possible priority,
which is guaranteed to be above configMAX_SYSCALL_INTERRUPT_PRIORITY,
and therefore also guaranteed to be invalid.
FreeRTOS maintains separate thread and ISR API functions to ensure
interrupt entry is as fast and simple as possible.
The following links provide detailed information:
http://www.freertos.org/RTOS-Cortex-M3-M4.html
http://www.freertos.org/FAQHelp.html */
configASSERT( ucCurrentPriority >= ucMaxSysCallPriority );
}
/* Priority grouping: The interrupt controller (NVIC) allows the bits
that define each interrupt's priority to be split between bits that
define the interrupt's pre-emption priority bits and bits that define
the interrupt's sub-priority. For simplicity all bits must be defined
to be pre-emption priority bits. The following assertion will fail if
this is not the case (if some bits represent a sub-priority).
If the application only uses CMSIS libraries for interrupt
configuration then the correct setting can be achieved on all Cortex-M
devices by calling NVIC_SetPriorityGrouping( 0 ); before starting the
scheduler. Note however that some vendor specific peripheral libraries
assume a non-zero priority group setting, in which cases using a value
of zero will result in unpredicable behaviour. */
configASSERT( NVIC_GetPriorityGrouping() <= ulMaxPRIGROUPValue );
}
#endif /* configASSERT_DEFINED */

View File

@ -0,0 +1,304 @@
/*
* FreeRTOS Kernel V10.0.0
* Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software. If you wish to use our Amazon
* FreeRTOS name, please do so in a fair use way that does not cause confusion.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
* http://www.FreeRTOS.org
* http://aws.amazon.com/freertos
*
* 1 tab == 4 spaces!
*/
/* Scheduler includes. */
#include "FreeRTOS.h"
#include "task.h"
#include "app_util.h"
#ifdef SOFTDEVICE_PRESENT
#include "nrf_soc.h"
#include "nrf_sdh.h"
#include "app_error.h"
#include "app_util_platform.h"
#endif
/*-----------------------------------------------------------
* Implementation of functions defined in portable.h for the ARM CM4F port.
* CMSIS compatible layer to menage SysTick ticking source.
*----------------------------------------------------------*/
#if configTICK_SOURCE == FREERTOS_USE_SYSTICK
#ifndef configSYSTICK_CLOCK_HZ
#define configSYSTICK_CLOCK_HZ configCPU_CLOCK_HZ
/* Ensure the SysTick is clocked at the same frequency as the core. */
#define portNVIC_SYSTICK_CLK_BIT ( SysTick_CTRL_CLKSOURCE_Msk )
#else
/* The way the SysTick is clocked is not modified in case it is not the same
as the core. */
#define portNVIC_SYSTICK_CLK_BIT ( 0 )
#endif
#if configUSE_TICKLESS_IDLE == 1
#error SysTick port for RF52 does not support tickless idle. Use RTC mode instead.
#endif /* configUSE_TICKLESS_IDLE */
/*-----------------------------------------------------------*/
void xPortSysTickHandler( void )
{
/* The SysTick runs at the lowest interrupt priority, so when this interrupt
executes all interrupts must be unmasked. There is therefore no need to
save and then restore the interrupt mask value as its value is already
known. */
( void ) portSET_INTERRUPT_MASK_FROM_ISR();
{
/* Increment the RTOS tick. */
if ( xTaskIncrementTick() != pdFALSE )
{
/* A context switch is required. Context switching is performed in
the PendSV interrupt. Pend the PendSV interrupt. */
SCB->ICSR = SCB_ICSR_PENDSVSET_Msk;
__SEV();
}
}
portCLEAR_INTERRUPT_MASK_FROM_ISR( 0 );
}
/*-----------------------------------------------------------*/
/*
* Setup the systick timer to generate the tick interrupts at the required
* frequency.
*/
void vPortSetupTimerInterrupt( void )
{
/* Set interrupt priority */
NVIC_SetPriority(SysTick_IRQn, configKERNEL_INTERRUPT_PRIORITY);
/* Configure SysTick to interrupt at the requested rate. */
SysTick->LOAD = ROUNDED_DIV(configSYSTICK_CLOCK_HZ, configTICK_RATE_HZ) - 1UL;
SysTick->CTRL = ( portNVIC_SYSTICK_CLK_BIT | SysTick_CTRL_TICKINT_Msk | SysTick_CTRL_ENABLE_Msk );
}
/*-----------------------------------------------------------*/
#elif configTICK_SOURCE == FREERTOS_USE_RTC
#if configUSE_16_BIT_TICKS == 1
#error This port does not support 16 bit ticks.
#endif
#include "nrf_rtc.h"
#include "nrf_drv_clock.h"
/*-----------------------------------------------------------*/
void xPortSysTickHandler( void )
{
#if configUSE_TICKLESS_IDLE == 1
nrf_rtc_event_clear(portNRF_RTC_REG, NRF_RTC_EVENT_COMPARE_0);
#endif
BaseType_t switch_req = pdFALSE;
uint32_t isrstate = portSET_INTERRUPT_MASK_FROM_ISR();
uint32_t systick_counter = nrf_rtc_counter_get(portNRF_RTC_REG);
nrf_rtc_event_clear(portNRF_RTC_REG, NRF_RTC_EVENT_TICK);
if (configUSE_DISABLE_TICK_AUTO_CORRECTION_DEBUG == 0)
{
/* check FreeRTOSConfig.h file for more details on configUSE_DISABLE_TICK_AUTO_CORRECTION_DEBUG */
TickType_t diff;
diff = (systick_counter - xTaskGetTickCount()) & portNRF_RTC_MAXTICKS;
/* At most 1 step if scheduler is suspended - the xTaskIncrementTick
* would return the tick state from the moment when suspend function was called. */
if ((diff > 1) && (xTaskGetSchedulerState() != taskSCHEDULER_RUNNING))
{
diff = 1;
}
while ((diff--) > 0)
{
switch_req |= xTaskIncrementTick();
}
}
else
{
switch_req = xTaskIncrementTick();
}
/* Increment the RTOS tick as usual which checks if there is a need for rescheduling */
if ( switch_req != pdFALSE )
{
/* A context switch is required. Context switching is performed in
the PendSV interrupt. Pend the PendSV interrupt. */
SCB->ICSR = SCB_ICSR_PENDSVSET_Msk;
__SEV();
}
portCLEAR_INTERRUPT_MASK_FROM_ISR( isrstate );
}
/*
* Setup the RTC time to generate the tick interrupts at the required
* frequency.
*/
void vPortSetupTimerInterrupt( void )
{
/* Request LF clock */
nrf_drv_clock_lfclk_request(NULL);
/* Configure SysTick to interrupt at the requested rate. */
nrf_rtc_prescaler_set(portNRF_RTC_REG, portNRF_RTC_PRESCALER);
nrf_rtc_int_enable (portNRF_RTC_REG, RTC_INTENSET_TICK_Msk);
nrf_rtc_task_trigger (portNRF_RTC_REG, NRF_RTC_TASK_CLEAR);
nrf_rtc_task_trigger (portNRF_RTC_REG, NRF_RTC_TASK_START);
nrf_rtc_event_enable(portNRF_RTC_REG, RTC_EVTEN_OVRFLW_Msk);
NVIC_SetPriority(portNRF_RTC_IRQn, configKERNEL_INTERRUPT_PRIORITY);
NVIC_EnableIRQ(portNRF_RTC_IRQn);
}
#if configUSE_TICKLESS_IDLE == 1
void vPortSuppressTicksAndSleep( TickType_t xExpectedIdleTime )
{
/*
* Implementation note:
*
* To help debugging the option configUSE_TICKLESS_IDLE_SIMPLE_DEBUG was presented.
* This option would make sure that even if program execution was stopped inside
* this function no more than expected number of ticks would be skipped.
*
* Normally RTC works all the time even if firmware execution was stopped
* and that may lead to skipping too much of ticks.
*/
TickType_t enterTime;
/* Make sure the SysTick reload value does not overflow the counter. */
if ( xExpectedIdleTime > portNRF_RTC_MAXTICKS - configEXPECTED_IDLE_TIME_BEFORE_SLEEP )
{
xExpectedIdleTime = portNRF_RTC_MAXTICKS - configEXPECTED_IDLE_TIME_BEFORE_SLEEP;
}
/* Block all the interrupts globally */
#ifdef SOFTDEVICE_PRESENT
do{
uint8_t dummy = 0;
uint32_t err_code = sd_nvic_critical_region_enter(&dummy);
APP_ERROR_CHECK(err_code);
}while (0);
#else
__disable_irq();
#endif
enterTime = nrf_rtc_counter_get(portNRF_RTC_REG);
if ( eTaskConfirmSleepModeStatus() != eAbortSleep )
{
TickType_t xModifiableIdleTime;
TickType_t wakeupTime = (enterTime + xExpectedIdleTime) & portNRF_RTC_MAXTICKS;
/* Stop tick events */
nrf_rtc_int_disable(portNRF_RTC_REG, NRF_RTC_INT_TICK_MASK);
/* Configure CTC interrupt */
nrf_rtc_cc_set(portNRF_RTC_REG, 0, wakeupTime);
nrf_rtc_event_clear(portNRF_RTC_REG, NRF_RTC_EVENT_COMPARE_0);
nrf_rtc_int_enable(portNRF_RTC_REG, NRF_RTC_INT_COMPARE0_MASK);
__DSB();
/* Sleep until something happens. configPRE_SLEEP_PROCESSING() can
* set its parameter to 0 to indicate that its implementation contains
* its own wait for interrupt or wait for event instruction, and so wfi
* should not be executed again. However, the original expected idle
* time variable must remain unmodified, so a copy is taken. */
xModifiableIdleTime = xExpectedIdleTime;
configPRE_SLEEP_PROCESSING( xModifiableIdleTime );
if ( xModifiableIdleTime > 0 )
{
#ifdef SOFTDEVICE_PRESENT
if (nrf_sdh_is_enabled())
{
// Fix ERRATA 87 (https://infocenter.nordicsemi.com/index.jsp?topic=%252Fcom.nordic.infocenter.sdk5.v11.0.0%252Findex.html&cp=4_0_0)
// Clear FPU interrupt before going to sleep. This prevent unexpected wake-up.
#define FPU_EXCEPTION_MASK 0x0000009F
/* Clear exceptions and PendingIRQ from the FPU unit */
__set_FPSCR(__get_FPSCR() & ~(FPU_EXCEPTION_MASK));
(void) __get_FPSCR();
NVIC_ClearPendingIRQ(FPU_IRQn);
uint32_t err_code = sd_app_evt_wait();
APP_ERROR_CHECK(err_code);
}
else
#endif
{
/* No SD - we would just block interrupts globally.
* BASEPRI cannot be used for that because it would prevent WFE from wake up.
*/
do{
__WFE();
} while (0 == (NVIC->ISPR[0] | NVIC->ISPR[1]));
}
}
configPOST_SLEEP_PROCESSING( xExpectedIdleTime );
nrf_rtc_int_disable(portNRF_RTC_REG, NRF_RTC_INT_COMPARE0_MASK);
nrf_rtc_event_clear(portNRF_RTC_REG, NRF_RTC_EVENT_COMPARE_0);
/* Correct the system ticks */
{
TickType_t diff;
TickType_t exitTime;
nrf_rtc_event_clear(portNRF_RTC_REG, NRF_RTC_EVENT_TICK);
nrf_rtc_int_enable (portNRF_RTC_REG, NRF_RTC_INT_TICK_MASK);
exitTime = nrf_rtc_counter_get(portNRF_RTC_REG);
diff = (exitTime - enterTime) & portNRF_RTC_MAXTICKS;
/* It is important that we clear pending here so that our corrections are latest and in sync with tick_interrupt handler */
NVIC_ClearPendingIRQ(portNRF_RTC_IRQn);
if ((configUSE_TICKLESS_IDLE_SIMPLE_DEBUG) && (diff > xExpectedIdleTime))
{
diff = xExpectedIdleTime;
}
if (diff > 0)
{
vTaskStepTick(diff);
}
}
}
#ifdef SOFTDEVICE_PRESENT
uint32_t err_code = sd_nvic_critical_region_exit(0);
APP_ERROR_CHECK(err_code);
#else
__enable_irq();
#endif
}
#endif // configUSE_TICKLESS_IDLE
#else // configTICK_SOURCE
#error Unsupported configTICK_SOURCE value
#endif // configTICK_SOURCE == FREERTOS_USE_SYSTICK

36
src/FreeRTOS/portmacro.h Normal file
View File

@ -0,0 +1,36 @@
/*
* FreeRTOS Kernel V10.0.0
* Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software. If you wish to use our Amazon
* FreeRTOS name, please do so in a fair use way that does not cause confusion.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
* http://www.FreeRTOS.org
* http://aws.amazon.com/freertos
*
* 1 tab == 4 spaces!
*/
#ifndef PORTMACRO_H
#define PORTMACRO_H
#include "portmacro_cmsis.h"
#endif /* PORTMACRO_H */

View File

@ -0,0 +1,187 @@
/*
* FreeRTOS Kernel V10.0.0
* Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.
*
* Permission is hereby granted, free of charge, to any person obtaining a copy of
* this software and associated documentation files (the "Software"), to deal in
* the Software without restriction, including without limitation the rights to
* use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
* the Software, and to permit persons to whom the Software is furnished to do so,
* subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software. If you wish to use our Amazon
* FreeRTOS name, please do so in a fair use way that does not cause confusion.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
* FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
* COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
* IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
* CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*
* http://www.FreeRTOS.org
* http://aws.amazon.com/freertos
*
* 1 tab == 4 spaces!
*/
#ifndef PORTMACRO_CMSIS_H
#define PORTMACRO_CMSIS_H
#include "app_util.h"
#ifdef __cplusplus
extern "C" {
#endif
/*-----------------------------------------------------------
* Port specific definitions.
*
* The settings in this file configure FreeRTOS correctly for the
* given hardware and compiler.
*
* These settings should not be altered.
*-----------------------------------------------------------
*/
/* Type definitions. */
#define portCHAR char
#define portFLOAT float
#define portDOUBLE double
#define portLONG long
#define portSHORT short
#define portSTACK_TYPE uint32_t
#define portBASE_TYPE long
typedef portSTACK_TYPE StackType_t;
typedef long BaseType_t;
typedef unsigned long UBaseType_t;
#if ( configUSE_16_BIT_TICKS == 1 )
typedef uint16_t TickType_t;
#define portMAX_DELAY ( TickType_t ) 0xffff
#else
typedef uint32_t TickType_t;
#define portMAX_DELAY ( TickType_t ) 0xffffffffUL
/* 32-bit tick type on a 32-bit architecture, so reads of the tick count do
not need to be guarded with a critical section. */
#define portTICK_TYPE_IS_ATOMIC 1
#endif
/*-----------------------------------------------------------*/
/* Architecture specifics. */
#define portSTACK_GROWTH ( -1 )
#define portTICK_PERIOD_MS ( ( TickType_t ) 1000 / configTICK_RATE_HZ )
#define portBYTE_ALIGNMENT 8
/* RTC register */
#define portNRF_RTC_REG NRF_RTC1
/* IRQn used by the selected RTC */
#define portNRF_RTC_IRQn RTC1_IRQn
/* Constants required to manipulate the NVIC. */
#define portNRF_RTC_PRESCALER ( (uint32_t) (ROUNDED_DIV(configSYSTICK_CLOCK_HZ, configTICK_RATE_HZ) - 1) )
/* Maximum RTC ticks */
#define portNRF_RTC_MAXTICKS ((1U<<24)-1U)
/*-----------------------------------------------------------*/
/* Scheduler utilities. */
#define portYIELD() do \
{ \
/* Set a PendSV to request a context switch. */ \
SCB->ICSR = SCB_ICSR_PENDSVSET_Msk; \
__SEV(); \
/* Barriers are normally not required but do ensure the code is completely \
within the specified behaviour for the architecture. */ \
__DSB(); \
__ISB(); \
}while (0)
#define portEND_SWITCHING_ISR( xSwitchRequired ) if ( (xSwitchRequired) != pdFALSE ) portYIELD()
#define portYIELD_FROM_ISR( x ) portEND_SWITCHING_ISR( x )
/*-----------------------------------------------------------*/
/* Critical section management. */
extern void vPortEnterCritical( void );
extern void vPortExitCritical( void );
#define portSET_INTERRUPT_MASK_FROM_ISR() ulPortRaiseBASEPRI()
#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x) vPortSetBASEPRI(x)
#define portDISABLE_INTERRUPTS() vPortRaiseBASEPRI()
#define portENABLE_INTERRUPTS() vPortSetBASEPRI(0)
#define portENTER_CRITICAL() vPortEnterCritical()
#define portEXIT_CRITICAL() vPortExitCritical()
/*-----------------------------------------------------------*/
/* Task function macros as described on the FreeRTOS.org WEB site. These are
not necessary for to use this port. They are defined so the common demo files
(which build with all the ports) will build. */
#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters )
#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters )
/*-----------------------------------------------------------*/
/* Tickless idle/low power functionality. */
#ifndef portSUPPRESS_TICKS_AND_SLEEP
extern void vPortSuppressTicksAndSleep( TickType_t xExpectedIdleTime );
#define portSUPPRESS_TICKS_AND_SLEEP( xExpectedIdleTime ) vPortSuppressTicksAndSleep( xExpectedIdleTime )
#endif
/*-----------------------------------------------------------*/
/* Architecture specific optimisations. */
#ifndef configUSE_PORT_OPTIMISED_TASK_SELECTION
#define configUSE_PORT_OPTIMISED_TASK_SELECTION 1
#endif
#if configUSE_PORT_OPTIMISED_TASK_SELECTION == 1
/* Count leading zeros helper. */
#define ucPortCountLeadingZeros( bits ) __CLZ( bits )
/* Check the configuration. */
#if ( configMAX_PRIORITIES > 32 )
#error configUSE_PORT_OPTIMISED_TASK_SELECTION can only be set to 1 when configMAX_PRIORITIES is less than or equal to 32. It is very rare that a system requires more than 10 to 15 difference priorities as tasks that share a priority will time slice.
#endif
/* Store/clear the ready priorities in a bit map. */
#define portRECORD_READY_PRIORITY( uxPriority, uxReadyPriorities ) ( uxReadyPriorities ) |= ( 1UL << ( uxPriority ) )
#define portRESET_READY_PRIORITY( uxPriority, uxReadyPriorities ) ( uxReadyPriorities ) &= ~( 1UL << ( uxPriority ) )
/*-----------------------------------------------------------*/
#define portGET_HIGHEST_PRIORITY( uxTopPriority, uxReadyPriorities ) uxTopPriority = ( 31 - ucPortCountLeadingZeros( ( uxReadyPriorities ) ) )
#endif /* configUSE_PORT_OPTIMISED_TASK_SELECTION */
/*-----------------------------------------------------------*/
#ifdef configASSERT
void vPortValidateInterruptPriority( void );
#define portASSERT_IF_INTERRUPT_PRIORITY_INVALID() vPortValidateInterruptPriority()
#endif
/*-----------------------------------------------------------*/
#define vPortSetBASEPRI( ulNewMaskValue ) __set_BASEPRI(ulNewMaskValue)
/*-----------------------------------------------------------*/
#define vPortRaiseBASEPRI( ) vPortSetBASEPRI(configMAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS))
/*-----------------------------------------------------------*/
__STATIC_INLINE uint32_t ulPortRaiseBASEPRI( void )
{
uint32_t ulOriginalBASEPRI = __get_BASEPRI();
vPortRaiseBASEPRI();
return ulOriginalBASEPRI;
}
/*-----------------------------------------------------------*/
#ifdef __cplusplus
}
#endif
#endif /* PORTMACRO_CMSIS_H */

View File

@ -78,9 +78,9 @@
#define configENABLE_BACKWARD_COMPATIBILITY 1
/* Hook function related definitions. */
#define configUSE_IDLE_HOOK 1
#define configUSE_IDLE_HOOK 0
#define configUSE_TICK_HOOK 0
#define configCHECK_FOR_STACK_OVERFLOW 2
#define configCHECK_FOR_STACK_OVERFLOW 0
#define configUSE_MALLOC_FAILED_HOOK 0
/* Run time and task stats gathering related definitions. */

View File

@ -21,7 +21,7 @@ void NrfLogger::Process(void*) {
NRF_LOG_INFO("Logger task started!");
while (1) {
NRF_LOG_FLUSH();
vTaskSuspend(nullptr);
vTaskDelay(100); // Not good for power consumption, it will wake up every 100ms...
}
}

View File

@ -36,16 +36,6 @@ Pinetime::Controllers::DateTime dateTimeController;
static constexpr uint8_t pinButton = 13;
static constexpr uint8_t pinTouchIrq = 28;
extern "C" {
void vApplicationIdleHook() {
logger.Resume();
}
void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed portCHAR *pcTaskName ) {
bsp_board_led_on(3);
}
}
void nrfx_gpiote_evt_handler(nrfx_gpiote_pin_t pin, nrf_gpiote_polarity_t action) {
if(pin == pinTouchIrq) {
displayApp->PushMessage(Pinetime::Applications::DisplayApp::Messages::TouchEvent);

View File

@ -8452,15 +8452,15 @@
// <e> NRF_LOG_ENABLED - nrf_log - Logger
//==========================================================
#ifndef NRF_LOG_ENABLED
#define NRF_LOG_ENABLED 1
#define NRF_LOG_ENABLED 0
#endif
#ifndef NRF_LOG_BACKEND_RTT_ENABLED
#define NRF_LOG_BACKEND_RTT_ENABLED 1
#define NRF_LOG_BACKEND_RTT_ENABLED 0
#endif
#ifndef NRF_LOG_BACKEND_SERIAL_USES_RTT
#define NRF_LOG_BACKEND_SERIAL_USES_RTT 1
#define NRF_LOG_BACKEND_SERIAL_USES_RTT 0
#endif
// <h> Log message pool - Configuration of log message pool