38         #error This port can only be used when the project options are configured to enable hardware floating point support.    41 #ifndef configSYSTICK_CLOCK_HZ    42         #define configSYSTICK_CLOCK_HZ configCPU_CLOCK_HZ    44         #define portNVIC_SYSTICK_CLK_BIT        ( 1UL << 2UL )    48         #define portNVIC_SYSTICK_CLK_BIT        ( 0 )    52 #define portNVIC_SYSTICK_CTRL_REG                       ( * ( ( volatile uint32_t * ) 0xe000e010 ) )    53 #define portNVIC_SYSTICK_LOAD_REG                       ( * ( ( volatile uint32_t * ) 0xe000e014 ) )    54 #define portNVIC_SYSTICK_CURRENT_VALUE_REG      ( * ( ( volatile uint32_t * ) 0xe000e018 ) )    55 #define portNVIC_SYSPRI2_REG                            ( * ( ( volatile uint32_t * ) 0xe000ed20 ) )    57 #define portNVIC_SYSTICK_INT_BIT                        ( 1UL << 1UL )    58 #define portNVIC_SYSTICK_ENABLE_BIT                     ( 1UL << 0UL )    59 #define portNVIC_SYSTICK_COUNT_FLAG_BIT         ( 1UL << 16UL )    60 #define portNVIC_PENDSVCLEAR_BIT                        ( 1UL << 27UL )    61 #define portNVIC_PEND_SYSTICK_CLEAR_BIT         ( 1UL << 25UL )    63 #define portNVIC_PENDSV_PRI                                     ( ( ( uint32_t ) configKERNEL_INTERRUPT_PRIORITY ) << 16UL )    64 #define portNVIC_SYSTICK_PRI                            ( ( ( uint32_t ) configKERNEL_INTERRUPT_PRIORITY ) << 24UL )    67 #define portFIRST_USER_INTERRUPT_NUMBER         ( 16 )    68 #define portNVIC_IP_REGISTERS_OFFSET_16         ( 0xE000E3F0 )    69 #define portAIRCR_REG                                           ( * ( ( volatile uint32_t * ) 0xE000ED0C ) )    70 #define portMAX_8_BIT_VALUE                                     ( ( uint8_t ) 0xff )    71 #define portTOP_BIT_OF_BYTE                                     ( ( uint8_t ) 0x80 )    72 #define portMAX_PRIGROUP_BITS                           ( ( uint8_t ) 7 )    73 #define portPRIORITY_GROUP_MASK                         ( 0x07UL << 8UL )    74 #define portPRIGROUP_SHIFT                                      ( 8UL )    77 #define portVECTACTIVE_MASK                                     ( 0xFFUL )    80 #define portFPCCR                                                       ( ( volatile uint32_t * ) 0xe000ef34 )     81 #define portASPEN_AND_LSPEN_BITS                        ( 0x3UL << 30UL )    84 #define portINITIAL_XPSR                                        ( 0x01000000 )    85 #define portINITIAL_EXC_RETURN                          ( 0xfffffffd )    88 #define portMAX_24_BIT_NUMBER                           ( 0xffffffUL )    92 #define portSTART_ADDRESS_MASK          ( ( StackType_t ) 0xfffffffeUL )    97 #define portMISSED_COUNTS_FACTOR                        ( 45UL )   102 #ifdef configTASK_RETURN_ADDRESS   103         #define portTASK_RETURN_ADDRESS configTASK_RETURN_ADDRESS   105         #define portTASK_RETURN_ADDRESS prvTaskExitError   146 #if( configUSE_TICKLESS_IDLE == 1 )   147         static uint32_t ulTimerCountsForOneTick = 0;
   154 #if( configUSE_TICKLESS_IDLE == 1 )   155         static uint32_t xMaximumPossibleSuppressedTicks = 0;
   162 #if( configUSE_TICKLESS_IDLE == 1 )   163         static uint32_t ulStoppedTimerCompensation = 0;
   171 #if( configASSERT_DEFINED == 1 )   172          static uint8_t ucMaxSysCallPriority = 0;
   173          static uint32_t ulMaxPRIGROUPValue = 0;
   214 volatile uint32_t ulDummy = 0;
   224         while( ulDummy == 0 )
   240                                         "       ldr     r3, pxCurrentTCBConst2          \n"    243                                         "       ldmia r0!, {r4-r11, r14}                \n"    247                                         "       msr     basepri, r0                                     \n"   251                                         "pxCurrentTCBConst2: .word pxCurrentTCB                         \n"   263                                         " ldr r0, =0xE000ED08   \n"    268                                         " msr control, r0               \n"   288         #if( configASSERT_DEFINED == 1 )   290                 volatile uint32_t ulOriginalPriority;
   292                 volatile uint8_t ucMaxPriorityValue;
   300                 ulOriginalPriority = *pucFirstUserPriorityRegister;
   307                 ucMaxPriorityValue = *pucFirstUserPriorityRegister;
   317                         ulMaxPRIGROUPValue--;
   318                         ucMaxPriorityValue <<= ( uint8_t ) 0x01;
   321                 #ifdef __NVIC_PRIO_BITS   330                 #ifdef configPRIO_BITS   346                 *pucFirstUserPriorityRegister = ulOriginalPriority;
   359         uxCriticalNesting = 0;
   402         if( uxCriticalNesting == 1 )
   413         if( uxCriticalNesting == 0 )
   429         "       ldr     r3, pxCurrentTCBConst                   \n"    434         "       vstmdbeq r0!, {s16-s31}                         \n"   436         "       stmdb r0!, {r4-r11, r14}                        \n"    439         "       stmdb sp!, {r0, r3}                                     \n"   442         "       msr basepri, r0                                         \n"   446         "       bl vTaskSwitchContext                           \n"   448         "       msr basepri, r0                                         \n"   449         "       ldmia sp!, {r0, r3}                                     \n"   454         "       ldmia r0!, {r4-r11, r14}                        \n"    458         "       vldmiaeq r0!, {s16-s31}                         \n"   463         #ifdef WORKAROUND_PMU_CM001    464                 #if WORKAROUND_PMU_CM001 == 1   473         "pxCurrentTCBConst: .word pxCurrentTCB  \n"   499 #if( configUSE_TICKLESS_IDLE == 1 )   503         uint32_t ulReloadValue, ulCompleteTickPeriods, ulCompletedSysTickDecrements;
   507                 if( xExpectedIdleTime > xMaximumPossibleSuppressedTicks )
   509                         xExpectedIdleTime = xMaximumPossibleSuppressedTicks;
   522                 if( ulReloadValue > ulStoppedTimerCompensation )
   524                         ulReloadValue -= ulStoppedTimerCompensation;
   529                 __asm 
volatile( 
"cpsid i" ::: 
"memory" );
   530                 __asm 
volatile( 
"dsb" );
   531                 __asm 
volatile( 
"isb" );
   550                         __asm 
volatile( 
"cpsie i" ::: 
"memory" );
   569                         xModifiableIdleTime = xExpectedIdleTime;
   571                         if( xModifiableIdleTime > 0 )
   573                                 __asm 
volatile( 
"dsb" ::: 
"memory" );
   574                                 __asm 
volatile( 
"wfi" );
   575                                 __asm 
volatile( 
"isb" );
   582                         __asm 
volatile( 
"cpsie i" ::: 
"memory" );
   583                         __asm 
volatile( 
"dsb" );
   584                         __asm 
volatile( 
"isb" );
   590                         __asm 
volatile( 
"cpsid i" ::: 
"memory" );
   591                         __asm 
volatile( 
"dsb" );
   592                         __asm 
volatile( 
"isb" );
   610                                 uint32_t ulCalculatedLoadValue;
   621                                 if( ( ulCalculatedLoadValue < ulStoppedTimerCompensation ) || ( ulCalculatedLoadValue > ulTimerCountsForOneTick ) )
   623                                         ulCalculatedLoadValue = ( ulTimerCountsForOneTick - 1UL );
   631                                 ulCompleteTickPeriods = xExpectedIdleTime - 1UL;
   643                                 ulCompleteTickPeriods = ulCompletedSysTickDecrements / ulTimerCountsForOneTick;
   647                                 portNVIC_SYSTICK_LOAD_REG = ( ( ulCompleteTickPeriods + 1UL ) * ulTimerCountsForOneTick ) - ulCompletedSysTickDecrements;
   659                         __asm 
volatile( 
"cpsie i" ::: 
"memory" );
   673         #if( configUSE_TICKLESS_IDLE == 1 )   696                 "       ldr.w r0, =0xE000ED88           \n"    699                 "       orr r1, r1, #( 0xf << 20 )      \n"    706 #if( configASSERT_DEFINED == 1 )   708         void vPortValidateInterruptPriority( 
void )
   710         uint32_t ulCurrentInterrupt;
   711         uint8_t ucCurrentPriority;
   714                 __asm 
volatile( 
"mrs %0, ipsr" : 
"=r"( ulCurrentInterrupt ) :: 
"memory" );
   720                         ucCurrentPriority = pcInterruptPriorityRegisters[ ulCurrentInterrupt ];
   745                         configASSERT( ucCurrentPriority >= ucMaxSysCallPriority );
 #define portNVIC_SYSTICK_CLK_BIT
 
BaseType_t xPortStartScheduler(void)
 
void vTaskSwitchContext(void) PRIVILEGED_FUNCTION
 
#define configCPU_CLOCK_HZ
 
void xPortPendSVHandler(void xPortSysTickHandler void)
 
#define portMISSED_COUNTS_FACTOR
 
static void vPortEnableVFP(void)
 
void xPortSysTickHandler(void)
 
#define portINITIAL_EXC_RETURN
 
#define portENABLE_INTERRUPTS()
 
#define portDISABLE_INTERRUPTS()
 
#define configPRE_SLEEP_PROCESSING(x)
 
#define portPRIGROUP_SHIFT
 
#define portTOP_BIT_OF_BYTE
 
void vPortEnterCritical(void)
 
#define portNVIC_SYSPRI2_REG
 
void vPortSVCHandler(void)
 
unsigned long UBaseType_t
 
void vPortEndScheduler(void)
 
#define portNVIC_SYSTICK_PRI
 
void vPortSuppressTicksAndSleep(TickType_t xExpectedIdleTime)
 
void vTaskStepTick(const TickType_t xTicksToJump) PRIVILEGED_FUNCTION
 
#define portPRIORITY_GROUP_MASK
 
StackType_t * pxPortInitialiseStack(StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters) PRIVILEGED_FUNCTION
 
#define portNVIC_PENDSV_PRI
 
#define configPOST_SLEEP_PROCESSING(x)
 
#define portNVIC_SYSTICK_LOAD_REG
 
#define portNVIC_SYSTICK_CURRENT_VALUE_REG
 
#define portMAX_PRIGROUP_BITS
 
#define portFIRST_USER_INTERRUPT_NUMBER
 
#define portVECTACTIVE_MASK
 
#define portSTART_ADDRESS_MASK
 
#define configSYSTICK_CLOCK_HZ
 
#define portTASK_RETURN_ADDRESS
 
static void prvPortStartFirstTask(void)
 
BaseType_t xTaskIncrementTick(void) PRIVILEGED_FUNCTION
 
#define portNVIC_SYSTICK_INT_BIT
 
void vPortSetupTimerInterrupt(void)
 
eSleepModeStatus eTaskConfirmSleepModeStatus(void) PRIVILEGED_FUNCTION
 
#define portNVIC_SYSTICK_COUNT_FLAG_BIT
 
static void prvTaskExitError(void)
 
#define portNVIC_SYSTICK_CTRL_REG
 
#define configMAX_SYSCALL_INTERRUPT_PRIORITY
 
#define configTICK_RATE_HZ
 
#define portNVIC_IP_REGISTERS_OFFSET_16
 
#define portMAX_8_BIT_VALUE
 
#define portNVIC_SYSTICK_ENABLE_BIT
 
#define portMAX_24_BIT_NUMBER
 
void(* TaskFunction_t)(void *)
 
#define portASPEN_AND_LSPEN_BITS
 
portSTACK_TYPE StackType_t
 
#define portNVIC_PENDSVSET_BIT
 
#define portNVIC_INT_CTRL_REG
 
void vPortExitCritical(void)