www.freertos.org

Dependents:   Nucleo freertos_test FreeRTOS_test freertos_bluetooth ... more

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers port.c Source File

port.c

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