Update revision to use TI's mqtt and Freertos.

Dependencies:   mbed client server

Fork of cc3100_Test_mqtt_CM3 by David Fletcher

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers port.c Source File

port.c

00001 /*
00002     FreeRTOS V8.2.1 - Copyright (C) 2015 Real Time Engineers Ltd.
00003     All rights reserved
00004 
00005     VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
00006 
00007     This file is part of the FreeRTOS distribution.
00008 
00009     FreeRTOS is free software; you can redistribute it and/or modify it under
00010     the terms of the GNU General Public License (version 2) as published by the
00011     Free Software Foundation >>!AND MODIFIED BY!<< the FreeRTOS exception.
00012 
00013     ***************************************************************************
00014     >>!   NOTE: The modification to the GPL is included to allow you to     !<<
00015     >>!   distribute a combined work that includes FreeRTOS without being   !<<
00016     >>!   obliged to provide the source code for proprietary components     !<<
00017     >>!   outside of the FreeRTOS kernel.                                   !<<
00018     ***************************************************************************
00019 
00020     FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
00021     WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
00022     FOR A PARTICULAR PURPOSE.  Full license text is available on the following
00023     link: http://www.freertos.org/a00114.html
00024 
00025     ***************************************************************************
00026      *                                                                       *
00027      *    FreeRTOS provides completely free yet professionally developed,    *
00028      *    robust, strictly quality controlled, supported, and cross          *
00029      *    platform software that is more than just the market leader, it     *
00030      *    is the industry's de facto standard.                               *
00031      *                                                                       *
00032      *    Help yourself get started quickly while simultaneously helping     *
00033      *    to support the FreeRTOS project by purchasing a FreeRTOS           *
00034      *    tutorial book, reference manual, or both:                          *
00035      *    http://www.FreeRTOS.org/Documentation                              *
00036      *                                                                       *
00037     ***************************************************************************
00038 
00039     http://www.FreeRTOS.org/FAQHelp.html - Having a problem?  Start by reading
00040     the FAQ page "My application does not run, what could be wrong?".  Have you
00041     defined configASSERT()?
00042 
00043     http://www.FreeRTOS.org/support - In return for receiving this top quality
00044     embedded software for free we request you assist our global community by
00045     participating in the support forum.
00046 
00047     http://www.FreeRTOS.org/training - Investing in training allows your team to
00048     be as productive as possible as early as possible.  Now you can receive
00049     FreeRTOS training directly from Richard Barry, CEO of Real Time Engineers
00050     Ltd, and the world's leading authority on the world's leading RTOS.
00051 
00052     http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
00053     including FreeRTOS+Trace - an indispensable productivity tool, a DOS
00054     compatible FAT file system, and our tiny thread aware UDP/IP stack.
00055 
00056     http://www.FreeRTOS.org/labs - Where new FreeRTOS products go to incubate.
00057     Come and try FreeRTOS+TCP, our new open source TCP/IP stack for FreeRTOS.
00058 
00059     http://www.OpenRTOS.com - Real Time Engineers ltd. license FreeRTOS to High
00060     Integrity Systems ltd. to sell under the OpenRTOS brand.  Low cost OpenRTOS
00061     licenses offer ticketed support, indemnification and commercial middleware.
00062 
00063     http://www.SafeRTOS.com - High Integrity Systems also provide a safety
00064     engineered and independently SIL3 certified version for use in safety and
00065     mission critical applications that require provable dependability.
00066 
00067     1 tab == 4 spaces!
00068 */
00069 
00070 /*-----------------------------------------------------------
00071  * Implementation of functions defined in portable.h for the ARM CM3 port.
00072  *----------------------------------------------------------*/
00073 
00074 /* Scheduler includes. */
00075 #include "FreeRTOS.h"
00076 #include "task.h"
00077 
00078 #ifndef configKERNEL_INTERRUPT_PRIORITY
00079     #define configKERNEL_INTERRUPT_PRIORITY 255
00080 #endif
00081 
00082 #if configMAX_SYSCALL_INTERRUPT_PRIORITY == 0
00083     #error configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to 0.  See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html
00084 #endif
00085 
00086 #ifndef configSYSTICK_CLOCK_HZ
00087     #define configSYSTICK_CLOCK_HZ configCPU_CLOCK_HZ
00088     /* Ensure the SysTick is clocked at the same frequency as the core. */
00089     #define portNVIC_SYSTICK_CLK_BIT    ( 1UL << 2UL )
00090 #else
00091     /* The way the SysTick is clocked is not modified in case it is not the same
00092     as the core. */
00093     #define portNVIC_SYSTICK_CLK_BIT    ( 0 )
00094 #endif
00095 
00096 /* The __weak attribute does not work as you might expect with the Keil tools
00097 so the configOVERRIDE_DEFAULT_TICK_CONFIGURATION constant must be set to 1 if
00098 the application writer wants to provide their own implementation of
00099 vPortSetupTimerInterrupt().  Ensure configOVERRIDE_DEFAULT_TICK_CONFIGURATION
00100 is defined. */
00101 #ifndef configOVERRIDE_DEFAULT_TICK_CONFIGURATION
00102     #define configOVERRIDE_DEFAULT_TICK_CONFIGURATION 0
00103 #endif
00104 
00105 /* Constants required to manipulate the core.  Registers first... */
00106 #define portNVIC_SYSTICK_CTRL_REG           ( * ( ( volatile uint32_t * ) 0xe000e010 ) )
00107 #define portNVIC_SYSTICK_LOAD_REG           ( * ( ( volatile uint32_t * ) 0xe000e014 ) )
00108 #define portNVIC_SYSTICK_CURRENT_VALUE_REG  ( * ( ( volatile uint32_t * ) 0xe000e018 ) )
00109 #define portNVIC_SYSPRI2_REG                ( * ( ( volatile uint32_t * ) 0xe000ed20 ) )
00110 /* ...then bits in the registers. */
00111 #define portNVIC_SYSTICK_INT_BIT            ( 1UL << 1UL )
00112 #define portNVIC_SYSTICK_ENABLE_BIT         ( 1UL << 0UL )
00113 #define portNVIC_SYSTICK_COUNT_FLAG_BIT     ( 1UL << 16UL )
00114 #define portNVIC_PENDSVCLEAR_BIT            ( 1UL << 27UL )
00115 #define portNVIC_PEND_SYSTICK_CLEAR_BIT     ( 1UL << 25UL )
00116 
00117 /* Masks off all bits but the VECTACTIVE bits in the ICSR register. */
00118 #define portVECTACTIVE_MASK                 ( 0xFFUL )
00119 
00120 #define portNVIC_PENDSV_PRI                 ( ( ( uint32_t ) configKERNEL_INTERRUPT_PRIORITY ) << 16UL )
00121 #define portNVIC_SYSTICK_PRI                ( ( ( uint32_t ) configKERNEL_INTERRUPT_PRIORITY ) << 24UL )
00122 
00123 /* Constants required to check the validity of an interrupt priority. */
00124 #define portFIRST_USER_INTERRUPT_NUMBER     ( 16 )
00125 #define portNVIC_IP_REGISTERS_OFFSET_16     ( 0xE000E3F0 )
00126 #define portAIRCR_REG                       ( * ( ( volatile uint32_t * ) 0xE000ED0C ) )
00127 #define portMAX_8_BIT_VALUE                 ( ( uint8_t ) 0xff )
00128 #define portTOP_BIT_OF_BYTE                 ( ( uint8_t ) 0x80 )
00129 #define portMAX_PRIGROUP_BITS               ( ( uint8_t ) 7 )
00130 #define portPRIORITY_GROUP_MASK             ( 0x07UL << 8UL )
00131 #define portPRIGROUP_SHIFT                  ( 8UL )
00132 
00133 /* Constants required to set up the initial stack. */
00134 #define portINITIAL_XPSR            ( 0x01000000 )
00135 
00136 /* Constants used with memory barrier intrinsics. */
00137 #define portSY_FULL_READ_WRITE      ( 15 )
00138 
00139 /* The systick is a 24-bit counter. */
00140 #define portMAX_24_BIT_NUMBER               ( 0xffffffUL )
00141 
00142 /* A fiddle factor to estimate the number of SysTick counts that would have
00143 occurred while the SysTick counter is stopped during tickless idle
00144 calculations. */
00145 #define portMISSED_COUNTS_FACTOR            ( 45UL )
00146 
00147 /* Each task maintains its own interrupt status in the critical nesting
00148 variable. */
00149 static UBaseType_t uxCriticalNesting = 0xaaaaaaaa;
00150 
00151 /*
00152  * Setup the timer to generate the tick interrupts.  The implementation in this
00153  * file is weak to allow application writers to change the timer used to
00154  * generate the tick interrupt.
00155  */
00156 void vPortSetupTimerInterrupt( void );
00157 
00158 /*
00159  * Exception handlers.
00160  */
00161 void xPortPendSVHandler( void );
00162 void xPortSysTickHandler( void );
00163 void vPortSVCHandler( void );
00164 
00165 /*
00166  * Start first task is a separate function so it can be tested in isolation.
00167  */
00168 static void prvStartFirstTask( void );
00169 
00170 /*
00171  * Used to catch tasks that attempt to return from their implementing function.
00172  */
00173 static void prvTaskExitError( void );
00174 
00175 /*-----------------------------------------------------------*/
00176 
00177 /*
00178  * The number of SysTick increments that make up one tick period.
00179  */
00180 #if configUSE_TICKLESS_IDLE == 1
00181     static uint32_t ulTimerCountsForOneTick = 0;
00182 #endif /* configUSE_TICKLESS_IDLE */
00183 
00184 /*
00185  * The maximum number of tick periods that can be suppressed is limited by the
00186  * 24 bit resolution of the SysTick timer.
00187  */
00188 #if configUSE_TICKLESS_IDLE == 1
00189     static uint32_t xMaximumPossibleSuppressedTicks = 0;
00190 #endif /* configUSE_TICKLESS_IDLE */
00191 
00192 /*
00193  * Compensate for the CPU cycles that pass while the SysTick is stopped (low
00194  * power functionality only.
00195  */
00196 #if configUSE_TICKLESS_IDLE == 1
00197     static uint32_t ulStoppedTimerCompensation = 0;
00198 #endif /* configUSE_TICKLESS_IDLE */
00199 
00200 /*
00201  * Used by the portASSERT_IF_INTERRUPT_PRIORITY_INVALID() macro to ensure
00202  * FreeRTOS API functions are not called from interrupts that have been assigned
00203  * a priority above configMAX_SYSCALL_INTERRUPT_PRIORITY.
00204  */
00205 #if ( configASSERT_DEFINED == 1 )
00206      static uint8_t ucMaxSysCallPriority = 0;
00207      static uint32_t ulMaxPRIGROUPValue = 0;
00208      static const volatile uint8_t * const pcInterruptPriorityRegisters = ( uint8_t * ) portNVIC_IP_REGISTERS_OFFSET_16;
00209 #endif /* configASSERT_DEFINED */
00210 
00211 /*-----------------------------------------------------------*/
00212 
00213 /*
00214  * See header file for description.
00215  */
00216 StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters )
00217 {
00218     /* Simulate the stack frame as it would be created by a context switch
00219     interrupt. */
00220     pxTopOfStack--; /* Offset added to account for the way the MCU uses the stack on entry/exit of interrupts. */
00221     *pxTopOfStack = portINITIAL_XPSR;   /* xPSR */
00222     pxTopOfStack--;
00223     *pxTopOfStack = ( StackType_t ) pxCode; /* PC */
00224     pxTopOfStack--;
00225     *pxTopOfStack = ( StackType_t ) prvTaskExitError;   /* LR */
00226 
00227     pxTopOfStack -= 5;  /* R12, R3, R2 and R1. */
00228     *pxTopOfStack = ( StackType_t ) pvParameters;   /* R0 */
00229     pxTopOfStack -= 8;  /* R11, R10, R9, R8, R7, R6, R5 and R4. */
00230 
00231     return pxTopOfStack;
00232 }
00233 /*-----------------------------------------------------------*/
00234 
00235 static void prvTaskExitError( void )
00236 {
00237     /* A function that implements a task must not exit or attempt to return to
00238     its caller as there is nothing to return to.  If a task wants to exit it
00239     should instead call vTaskDelete( NULL ).
00240 
00241     Artificially force an assert() to be triggered if configASSERT() is
00242     defined, then stop here so application writers can catch the error. */
00243     configASSERT( uxCriticalNesting == ~0UL );
00244     portDISABLE_INTERRUPTS();
00245     for( ;; );
00246 }
00247 /*-----------------------------------------------------------*/
00248 
00249 __asm void vPortSVCHandler( void )
00250 {
00251     PRESERVE8
00252 
00253     ldr r3, =pxCurrentTCB   /* Restore the context. */
00254     ldr r1, [r3]            /* Use pxCurrentTCBConst to get the pxCurrentTCB address. */
00255     ldr r0, [r1]            /* The first item in pxCurrentTCB is the task top of stack. */
00256     ldmia r0!, {r4-r11}     /* Pop the registers that are not automatically saved on exception entry and the critical nesting count. */
00257     msr psp, r0             /* Restore the task stack pointer. */
00258     isb
00259     mov r0, #0
00260     msr basepri, r0
00261     orr r14, #0xd
00262     bx r14
00263 }
00264 /*-----------------------------------------------------------*/
00265 
00266 __asm void prvStartFirstTask( void )
00267 {
00268     PRESERVE8
00269 
00270     /* Use the NVIC offset register to locate the stack. */
00271     ldr r0, =0xE000ED08
00272     ldr r0, [r0]
00273     ldr r0, [r0]
00274 
00275     /* Set the msp back to the start of the stack. */
00276     msr msp, r0
00277     /* Globally enable interrupts. */
00278     cpsie i
00279     cpsie f
00280     dsb
00281     isb
00282     /* Call SVC to start the first task. */
00283     svc 0
00284     nop
00285     nop
00286 }
00287 /*-----------------------------------------------------------*/
00288 
00289 /*
00290  * See header file for description.
00291  */
00292 BaseType_t xPortStartScheduler( void )
00293 {
00294     #if( configASSERT_DEFINED == 1 )
00295     {
00296         volatile uint32_t ulOriginalPriority;
00297         volatile uint8_t * const pucFirstUserPriorityRegister = ( uint8_t * ) ( portNVIC_IP_REGISTERS_OFFSET_16 + portFIRST_USER_INTERRUPT_NUMBER );
00298         volatile uint8_t ucMaxPriorityValue;
00299 
00300         /* Determine the maximum priority from which ISR safe FreeRTOS API
00301         functions can be called.  ISR safe functions are those that end in
00302         "FromISR".  FreeRTOS maintains separate thread and ISR API functions to
00303         ensure interrupt entry is as fast and simple as possible.
00304 
00305         Save the interrupt priority value that is about to be clobbered. */
00306         ulOriginalPriority = *pucFirstUserPriorityRegister;
00307 
00308         /* Determine the number of priority bits available.  First write to all
00309         possible bits. */
00310         *pucFirstUserPriorityRegister = portMAX_8_BIT_VALUE;
00311 
00312         /* Read the value back to see how many bits stuck. */
00313         ucMaxPriorityValue = *pucFirstUserPriorityRegister;
00314 
00315         /* Use the same mask on the maximum system call priority. */
00316         ucMaxSysCallPriority = configMAX_SYSCALL_INTERRUPT_PRIORITY & ucMaxPriorityValue;
00317 
00318         /* Calculate the maximum acceptable priority group value for the number
00319         of bits read back. */
00320         ulMaxPRIGROUPValue = portMAX_PRIGROUP_BITS;
00321         while( ( ucMaxPriorityValue & portTOP_BIT_OF_BYTE ) == portTOP_BIT_OF_BYTE )
00322         {
00323             ulMaxPRIGROUPValue--;
00324             ucMaxPriorityValue <<= ( uint8_t ) 0x01;
00325         }
00326 
00327         /* Shift the priority group value back to its position within the AIRCR
00328         register. */
00329         ulMaxPRIGROUPValue <<= portPRIGROUP_SHIFT;
00330         ulMaxPRIGROUPValue &= portPRIORITY_GROUP_MASK;
00331 
00332         /* Restore the clobbered interrupt priority register to its original
00333         value. */
00334         *pucFirstUserPriorityRegister = ulOriginalPriority;
00335     }
00336     #endif /* conifgASSERT_DEFINED */
00337 
00338     /* Make PendSV and SysTick the lowest priority interrupts. */
00339     portNVIC_SYSPRI2_REG |= portNVIC_PENDSV_PRI;
00340     portNVIC_SYSPRI2_REG |= portNVIC_SYSTICK_PRI;
00341 
00342     /* Start the timer that generates the tick ISR.  Interrupts are disabled
00343     here already. */
00344     vPortSetupTimerInterrupt();
00345 
00346     /* Initialise the critical nesting count ready for the first task. */
00347     uxCriticalNesting = 0;
00348 
00349     /* Start the first task. */
00350     prvStartFirstTask();
00351 
00352     /* Should not get here! */
00353     return 0;
00354 }
00355 /*-----------------------------------------------------------*/
00356 
00357 void vPortEndScheduler( void )
00358 {
00359     /* Not implemented in ports where there is nothing to return to.
00360     Artificially force an assert. */
00361     configASSERT( uxCriticalNesting == 1000UL );
00362 }
00363 /*-----------------------------------------------------------*/
00364 
00365 void vPortYield( void )
00366 {
00367     /* Set a PendSV to request a context switch. */
00368     portNVIC_INT_CTRL_REG = portNVIC_PENDSVSET_BIT;
00369 
00370     /* Barriers are normally not required but do ensure the code is completely
00371     within the specified behaviour for the architecture. */
00372     __dsb( portSY_FULL_READ_WRITE );
00373     __isb( portSY_FULL_READ_WRITE );
00374 }
00375 /*-----------------------------------------------------------*/
00376 
00377 void vPortEnterCritical( void )
00378 {
00379     portDISABLE_INTERRUPTS();
00380     uxCriticalNesting++;
00381     __dsb( portSY_FULL_READ_WRITE );
00382     __isb( portSY_FULL_READ_WRITE );
00383 
00384     /* This is not the interrupt safe version of the enter critical function so
00385     assert() if it is being called from an interrupt context.  Only API
00386     functions that end in "FromISR" can be used in an interrupt.  Only assert if
00387     the critical nesting count is 1 to protect against recursive calls if the
00388     assert function also uses a critical section. */
00389     if( uxCriticalNesting == 1 )
00390     {
00391         configASSERT( ( portNVIC_INT_CTRL_REG & portVECTACTIVE_MASK ) == 0 );
00392     }
00393 }
00394 /*-----------------------------------------------------------*/
00395 
00396 void vPortExitCritical( void )
00397 {
00398     configASSERT( uxCriticalNesting );
00399     uxCriticalNesting--;
00400     if( uxCriticalNesting == 0 )
00401     {
00402         portENABLE_INTERRUPTS();
00403     }
00404 }
00405 /*-----------------------------------------------------------*/
00406 
00407 __asm void xPortPendSVHandler( void )
00408 {
00409     extern uxCriticalNesting;
00410     extern pxCurrentTCB;
00411     extern vTaskSwitchContext;
00412 
00413     PRESERVE8
00414 
00415     mrs r0, psp
00416     isb
00417 
00418     ldr r3, =pxCurrentTCB       /* Get the location of the current TCB. */
00419     ldr r2, [r3]
00420 
00421     stmdb r0!, {r4-r11}         /* Save the remaining registers. */
00422     str r0, [r2]                /* Save the new top of stack into the first member of the TCB. */
00423 
00424     stmdb sp!, {r3, r14}
00425     mov r0, #configMAX_SYSCALL_INTERRUPT_PRIORITY
00426     msr basepri, r0
00427     bl vTaskSwitchContext
00428     mov r0, #0
00429     msr basepri, r0
00430     ldmia sp!, {r3, r14}
00431 
00432     ldr r1, [r3]
00433     ldr r0, [r1]                /* The first item in pxCurrentTCB is the task top of stack. */
00434     ldmia r0!, {r4-r11}         /* Pop the registers and the critical nesting count. */
00435     msr psp, r0
00436     isb
00437     bx r14
00438     nop
00439 }
00440 /*-----------------------------------------------------------*/
00441 
00442 void xPortSysTickHandler( void )
00443 {
00444     /* The SysTick runs at the lowest interrupt priority, so when this interrupt
00445     executes all interrupts must be unmasked.  There is therefore no need to
00446     save and then restore the interrupt mask value as its value is already
00447     known. */
00448     ( void ) portSET_INTERRUPT_MASK_FROM_ISR();
00449     {
00450         /* Increment the RTOS tick. */
00451         if( xTaskIncrementTick() != pdFALSE )
00452         {
00453             /* A context switch is required.  Context switching is performed in
00454             the PendSV interrupt.  Pend the PendSV interrupt. */
00455             portNVIC_INT_CTRL_REG = portNVIC_PENDSVSET_BIT;
00456         }
00457     }
00458     portCLEAR_INTERRUPT_MASK_FROM_ISR( 0 );
00459 }
00460 /*-----------------------------------------------------------*/
00461 
00462 #if configUSE_TICKLESS_IDLE == 1
00463 
00464     __weak void vPortSuppressTicksAndSleep( TickType_t xExpectedIdleTime )
00465     {
00466     uint32_t ulReloadValue, ulCompleteTickPeriods, ulCompletedSysTickDecrements, ulSysTickCTRL;
00467     TickType_t xModifiableIdleTime;
00468 
00469         /* Make sure the SysTick reload value does not overflow the counter. */
00470         if( xExpectedIdleTime > xMaximumPossibleSuppressedTicks )
00471         {
00472             xExpectedIdleTime = xMaximumPossibleSuppressedTicks;
00473         }
00474 
00475         /* Stop the SysTick momentarily.  The time the SysTick is stopped for
00476         is accounted for as best it can be, but using the tickless mode will
00477         inevitably result in some tiny drift of the time maintained by the
00478         kernel with respect to calendar time. */
00479         portNVIC_SYSTICK_CTRL_REG &= ~portNVIC_SYSTICK_ENABLE_BIT;
00480 
00481         /* Calculate the reload value required to wait xExpectedIdleTime
00482         tick periods.  -1 is used because this code will execute part way
00483         through one of the tick periods. */
00484         ulReloadValue = portNVIC_SYSTICK_CURRENT_VALUE_REG + ( ulTimerCountsForOneTick * ( xExpectedIdleTime - 1UL ) );
00485         if( ulReloadValue > ulStoppedTimerCompensation )
00486         {
00487             ulReloadValue -= ulStoppedTimerCompensation;
00488         }
00489 
00490         /* Enter a critical section but don't use the taskENTER_CRITICAL()
00491         method as that will mask interrupts that should exit sleep mode. */
00492         __disable_irq();
00493 
00494         /* If a context switch is pending or a task is waiting for the scheduler
00495         to be unsuspended then abandon the low power entry. */
00496         if( eTaskConfirmSleepModeStatus() == eAbortSleep )
00497         {
00498             /* Restart from whatever is left in the count register to complete
00499             this tick period. */
00500             portNVIC_SYSTICK_LOAD_REG = portNVIC_SYSTICK_CURRENT_VALUE_REG;
00501 
00502             /* Restart SysTick. */
00503             portNVIC_SYSTICK_CTRL_REG |= portNVIC_SYSTICK_ENABLE_BIT;
00504 
00505             /* Reset the reload register to the value required for normal tick
00506             periods. */
00507             portNVIC_SYSTICK_LOAD_REG = ulTimerCountsForOneTick - 1UL;
00508 
00509             /* Re-enable interrupts - see comments above __disable_irq() call
00510             above. */
00511             __enable_irq();
00512         }
00513         else
00514         {
00515             /* Set the new reload value. */
00516             portNVIC_SYSTICK_LOAD_REG = ulReloadValue;
00517 
00518             /* Clear the SysTick count flag and set the count value back to
00519             zero. */
00520             portNVIC_SYSTICK_CURRENT_VALUE_REG = 0UL;
00521 
00522             /* Restart SysTick. */
00523             portNVIC_SYSTICK_CTRL_REG |= portNVIC_SYSTICK_ENABLE_BIT;
00524 
00525             /* Sleep until something happens.  configPRE_SLEEP_PROCESSING() can
00526             set its parameter to 0 to indicate that its implementation contains
00527             its own wait for interrupt or wait for event instruction, and so wfi
00528             should not be executed again.  However, the original expected idle
00529             time variable must remain unmodified, so a copy is taken. */
00530             xModifiableIdleTime = xExpectedIdleTime;
00531             configPRE_SLEEP_PROCESSING( xModifiableIdleTime );
00532             if( xModifiableIdleTime > 0 )
00533             {
00534                 __dsb( portSY_FULL_READ_WRITE );
00535                 __wfi();
00536                 __isb( portSY_FULL_READ_WRITE );
00537             }
00538             configPOST_SLEEP_PROCESSING( xExpectedIdleTime );
00539 
00540             /* Stop SysTick.  Again, the time the SysTick is stopped for is
00541             accounted for as best it can be, but using the tickless mode will
00542             inevitably result in some tiny drift of the time maintained by the
00543             kernel with respect to calendar time. */
00544             ulSysTickCTRL = portNVIC_SYSTICK_CTRL_REG;
00545             portNVIC_SYSTICK_CTRL_REG = ( ulSysTickCTRL & ~portNVIC_SYSTICK_ENABLE_BIT );
00546 
00547             /* Re-enable interrupts - see comments above __disable_irq() call
00548             above. */
00549             __enable_irq();
00550 
00551             if( ( ulSysTickCTRL & portNVIC_SYSTICK_COUNT_FLAG_BIT ) != 0 )
00552             {
00553                 uint32_t ulCalculatedLoadValue;
00554 
00555                 /* The tick interrupt has already executed, and the SysTick
00556                 count reloaded with ulReloadValue.  Reset the
00557                 portNVIC_SYSTICK_LOAD_REG with whatever remains of this tick
00558                 period. */
00559                 ulCalculatedLoadValue = ( ulTimerCountsForOneTick - 1UL ) - ( ulReloadValue - portNVIC_SYSTICK_CURRENT_VALUE_REG );
00560 
00561                 /* Don't allow a tiny value, or values that have somehow
00562                 underflowed because the post sleep hook did something
00563                 that took too long. */
00564                 if( ( ulCalculatedLoadValue < ulStoppedTimerCompensation ) || ( ulCalculatedLoadValue > ulTimerCountsForOneTick ) )
00565                 {
00566                     ulCalculatedLoadValue = ( ulTimerCountsForOneTick - 1UL );
00567                 }
00568 
00569                 portNVIC_SYSTICK_LOAD_REG = ulCalculatedLoadValue;
00570 
00571                 /* The tick interrupt handler will already have pended the tick
00572                 processing in the kernel.  As the pending tick will be
00573                 processed as soon as this function exits, the tick value
00574                 maintained by the tick is stepped forward by one less than the
00575                 time spent waiting. */
00576                 ulCompleteTickPeriods = xExpectedIdleTime - 1UL;
00577             }
00578             else
00579             {
00580                 /* Something other than the tick interrupt ended the sleep.
00581                 Work out how long the sleep lasted rounded to complete tick
00582                 periods (not the ulReload value which accounted for part
00583                 ticks). */
00584                 ulCompletedSysTickDecrements = ( xExpectedIdleTime * ulTimerCountsForOneTick ) - portNVIC_SYSTICK_CURRENT_VALUE_REG;
00585 
00586                 /* How many complete tick periods passed while the processor
00587                 was waiting? */
00588                 ulCompleteTickPeriods = ulCompletedSysTickDecrements / ulTimerCountsForOneTick;
00589 
00590                 /* The reload value is set to whatever fraction of a single tick
00591                 period remains. */
00592                 portNVIC_SYSTICK_LOAD_REG = ( ( ulCompleteTickPeriods + 1 ) * ulTimerCountsForOneTick ) - ulCompletedSysTickDecrements;
00593             }
00594 
00595             /* Restart SysTick so it runs from portNVIC_SYSTICK_LOAD_REG
00596             again, then set portNVIC_SYSTICK_LOAD_REG back to its standard
00597             value.  The critical section is used to ensure the tick interrupt
00598             can only execute once in the case that the reload register is near
00599             zero. */
00600             portNVIC_SYSTICK_CURRENT_VALUE_REG = 0UL;
00601             portENTER_CRITICAL();
00602             {
00603                 portNVIC_SYSTICK_CTRL_REG |= portNVIC_SYSTICK_ENABLE_BIT;
00604                 vTaskStepTick( ulCompleteTickPeriods );
00605                 portNVIC_SYSTICK_LOAD_REG = ulTimerCountsForOneTick - 1UL;
00606             }
00607             portEXIT_CRITICAL();
00608         }
00609     }
00610 
00611 #endif /* #if configUSE_TICKLESS_IDLE */
00612 
00613 /*-----------------------------------------------------------*/
00614 
00615 /*
00616  * Setup the SysTick timer to generate the tick interrupts at the required
00617  * frequency.
00618  */
00619 #if configOVERRIDE_DEFAULT_TICK_CONFIGURATION == 0
00620 
00621     void vPortSetupTimerInterrupt( void )
00622     {
00623         /* Calculate the constants required to configure the tick interrupt. */
00624         #if configUSE_TICKLESS_IDLE == 1
00625         {
00626             ulTimerCountsForOneTick = ( configSYSTICK_CLOCK_HZ / configTICK_RATE_HZ );
00627             xMaximumPossibleSuppressedTicks = portMAX_24_BIT_NUMBER / ulTimerCountsForOneTick;
00628             ulStoppedTimerCompensation = portMISSED_COUNTS_FACTOR / ( configCPU_CLOCK_HZ / configSYSTICK_CLOCK_HZ );
00629         }
00630         #endif /* configUSE_TICKLESS_IDLE */
00631 
00632         /* Configure SysTick to interrupt at the requested rate. */
00633         portNVIC_SYSTICK_LOAD_REG = ( configSYSTICK_CLOCK_HZ / configTICK_RATE_HZ ) - 1UL;
00634         portNVIC_SYSTICK_CTRL_REG = ( portNVIC_SYSTICK_CLK_BIT | portNVIC_SYSTICK_INT_BIT | portNVIC_SYSTICK_ENABLE_BIT );
00635     }
00636 
00637 #endif /* configOVERRIDE_DEFAULT_TICK_CONFIGURATION */
00638 /*-----------------------------------------------------------*/
00639 
00640 __asm uint32_t ulPortSetInterruptMask( void )
00641 {
00642     PRESERVE8
00643 
00644     mrs r0, basepri
00645     mov r1, #configMAX_SYSCALL_INTERRUPT_PRIORITY
00646     msr basepri, r1
00647     bx r14
00648 }
00649 /*-----------------------------------------------------------*/
00650 
00651 __asm void vPortClearInterruptMask( uint32_t ulNewMask )
00652 {
00653     PRESERVE8
00654 
00655     msr basepri, r0
00656     bx r14
00657 }
00658 /*-----------------------------------------------------------*/
00659 
00660 __asm uint32_t vPortGetIPSR( void )
00661 {
00662     PRESERVE8
00663 
00664     mrs r0, ipsr
00665     bx r14
00666 }
00667 /*-----------------------------------------------------------*/
00668 
00669 #if( configASSERT_DEFINED == 1 )
00670 
00671     void vPortValidateInterruptPriority( void )
00672     {
00673     uint32_t ulCurrentInterrupt;
00674     uint8_t ucCurrentPriority;
00675 
00676         /* Obtain the number of the currently executing interrupt. */
00677         ulCurrentInterrupt = vPortGetIPSR();
00678 
00679         /* Is the interrupt number a user defined interrupt? */
00680         if( ulCurrentInterrupt >= portFIRST_USER_INTERRUPT_NUMBER )
00681         {
00682             /* Look up the interrupt's priority. */
00683             ucCurrentPriority = pcInterruptPriorityRegisters[ ulCurrentInterrupt ];
00684 
00685             /* The following assertion will fail if a service routine (ISR) for
00686             an interrupt that has been assigned a priority above
00687             configMAX_SYSCALL_INTERRUPT_PRIORITY calls an ISR safe FreeRTOS API
00688             function.  ISR safe FreeRTOS API functions must *only* be called
00689             from interrupts that have been assigned a priority at or below
00690             configMAX_SYSCALL_INTERRUPT_PRIORITY.
00691 
00692             Numerically low interrupt priority numbers represent logically high
00693             interrupt priorities, therefore the priority of the interrupt must
00694             be set to a value equal to or numerically *higher* than
00695             configMAX_SYSCALL_INTERRUPT_PRIORITY.
00696 
00697             Interrupts that use the FreeRTOS API must not be left at their
00698             default priority of zero as that is the highest possible priority,
00699             which is guaranteed to be above configMAX_SYSCALL_INTERRUPT_PRIORITY,
00700             and therefore also guaranteed to be invalid.
00701 
00702             FreeRTOS maintains separate thread and ISR API functions to ensure
00703             interrupt entry is as fast and simple as possible.
00704 
00705             The following links provide detailed information:
00706             http://www.freertos.org/RTOS-Cortex-M3-M4.html
00707             http://www.freertos.org/FAQHelp.html */
00708             configASSERT( ucCurrentPriority >= ucMaxSysCallPriority );
00709         }
00710 
00711         /* Priority grouping:  The interrupt controller (NVIC) allows the bits
00712         that define each interrupt's priority to be split between bits that
00713         define the interrupt's pre-emption priority bits and bits that define
00714         the interrupt's sub-priority.  For simplicity all bits must be defined
00715         to be pre-emption priority bits.  The following assertion will fail if
00716         this is not the case (if some bits represent a sub-priority).
00717 
00718         If the application only uses CMSIS libraries for interrupt
00719         configuration then the correct setting can be achieved on all Cortex-M
00720         devices by calling NVIC_SetPriorityGrouping( 0 ); before starting the
00721         scheduler.  Note however that some vendor specific peripheral libraries
00722         assume a non-zero priority group setting, in which cases using a value
00723         of zero will result in unpredicable behaviour. */
00724         configASSERT( ( portAIRCR_REG & portPRIORITY_GROUP_MASK ) <= ulMaxPRIGROUPValue );
00725     }
00726 
00727 #endif /* configASSERT_DEFINED */
00728 
00729 
00730