2 FreeRTOS V7.5.1 - Copyright (C) 2013 Real Time Engineers Ltd.
\r
4 VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
\r
6 ***************************************************************************
\r
8 * FreeRTOS provides completely free yet professionally developed, *
\r
9 * robust, strictly quality controlled, supported, and cross *
\r
10 * platform software that has become a de facto standard. *
\r
12 * Help yourself get started quickly and support the FreeRTOS *
\r
13 * project by purchasing a FreeRTOS tutorial book, reference *
\r
14 * manual, or both from: http://www.FreeRTOS.org/Documentation *
\r
18 ***************************************************************************
\r
20 This file is part of the FreeRTOS distribution.
\r
22 FreeRTOS is free software; you can redistribute it and/or modify it under
\r
23 the terms of the GNU General Public License (version 2) as published by the
\r
24 Free Software Foundation >>!AND MODIFIED BY!<< the FreeRTOS exception.
\r
26 >>! NOTE: The modification to the GPL is included to allow you to distribute
\r
27 >>! a combined work that includes FreeRTOS without being obliged to provide
\r
28 >>! the source code for proprietary components outside of the FreeRTOS
\r
31 FreeRTOS is distributed in the hope that it will be useful, but WITHOUT ANY
\r
32 WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
\r
33 FOR A PARTICULAR PURPOSE. Full license text is available from the following
\r
34 link: http://www.freertos.org/a00114.html
\r
38 ***************************************************************************
\r
40 * Having a problem? Start by reading the FAQ "My application does *
\r
41 * not run, what could be wrong?" *
\r
43 * http://www.FreeRTOS.org/FAQHelp.html *
\r
45 ***************************************************************************
\r
47 http://www.FreeRTOS.org - Documentation, books, training, latest versions,
\r
48 license and Real Time Engineers Ltd. contact details.
\r
50 http://www.FreeRTOS.org/plus - A selection of FreeRTOS ecosystem products,
\r
51 including FreeRTOS+Trace - an indispensable productivity tool, a DOS
\r
52 compatible FAT file system, and our tiny thread aware UDP/IP stack.
\r
54 http://www.OpenRTOS.com - Real Time Engineers ltd license FreeRTOS to High
\r
55 Integrity Systems to sell under the OpenRTOS brand. Low cost OpenRTOS
\r
56 licenses offer ticketed support, indemnification and middleware.
\r
58 http://www.SafeRTOS.com - High Integrity Systems also provide a safety
\r
59 engineered and independently SIL3 certified version for use in safety and
\r
60 mission critical applications that require provable dependability.
\r
65 /*-----------------------------------------------------------
\r
66 * Implementation of functions defined in portable.h for the ARM CM4F port.
\r
67 *----------------------------------------------------------*/
\r
69 /* Scheduler includes. */
\r
70 #include "FreeRTOS.h"
\r
73 #ifndef __TARGET_FPU_VFP
\r
74 #error This port can only be used when the project options are configured to enable hardware floating point support.
\r
77 #if configMAX_SYSCALL_INTERRUPT_PRIORITY == 0
\r
78 #error configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to 0. See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html
\r
81 #ifndef configSYSTICK_CLOCK_HZ
\r
82 #define configSYSTICK_CLOCK_HZ configCPU_CLOCK_HZ
\r
85 /* The __weak attribute does not work as you might expect with the Keil tools
\r
86 so the configOVERRIDE_DEFAULT_TICK_CONFIGURATION constant must be set to 1 if
\r
87 the application writer wants to provide their own implementation of
\r
88 vPortSetupTimerInterrupt(). Ensure configOVERRIDE_DEFAULT_TICK_CONFIGURATION
\r
90 #ifndef configOVERRIDE_DEFAULT_TICK_CONFIGURATION
\r
91 #define configOVERRIDE_DEFAULT_TICK_CONFIGURATION 0
\r
94 /* Constants required to manipulate the core. Registers first... */
\r
95 #define portNVIC_SYSTICK_CTRL_REG ( * ( ( volatile unsigned long * ) 0xe000e010 ) )
\r
96 #define portNVIC_SYSTICK_LOAD_REG ( * ( ( volatile unsigned long * ) 0xe000e014 ) )
\r
97 #define portNVIC_SYSTICK_CURRENT_VALUE_REG ( * ( ( volatile unsigned long * ) 0xe000e018 ) )
\r
98 #define portNVIC_SYSPRI2_REG ( * ( ( volatile unsigned long * ) 0xe000ed20 ) )
\r
99 /* ...then bits in the registers. */
\r
100 #define portNVIC_SYSTICK_CLK_BIT ( 1UL << 2UL )
\r
101 #define portNVIC_SYSTICK_INT_BIT ( 1UL << 1UL )
\r
102 #define portNVIC_SYSTICK_ENABLE_BIT ( 1UL << 0UL )
\r
103 #define portNVIC_SYSTICK_COUNT_FLAG_BIT ( 1UL << 16UL )
\r
104 #define portNVIC_PENDSVCLEAR_BIT ( 1UL << 27UL )
\r
105 #define portNVIC_PEND_SYSTICK_CLEAR_BIT ( 1UL << 25UL )
\r
107 #define portNVIC_PENDSV_PRI ( ( ( unsigned long ) configKERNEL_INTERRUPT_PRIORITY ) << 16UL )
\r
108 #define portNVIC_SYSTICK_PRI ( ( ( unsigned long ) configKERNEL_INTERRUPT_PRIORITY ) << 24UL )
\r
110 /* Constants required to check the validity of an interrupt prority. */
\r
111 #define portFIRST_USER_INTERRUPT_NUMBER ( 16 )
\r
112 #define portNVIC_IP_REGISTERS_OFFSET_16 ( 0xE000E3F0 )
\r
113 #define portAIRCR_REG ( * ( ( volatile unsigned long * ) 0xE000ED0C ) )
\r
114 #define portMAX_8_BIT_VALUE ( ( unsigned char ) 0xff )
\r
115 #define portTOP_BIT_OF_BYTE ( ( unsigned char ) 0x80 )
\r
116 #define portMAX_PRIGROUP_BITS ( ( unsigned char ) 7 )
\r
117 #define portPRIORITY_GROUP_MASK ( 0x07UL << 8UL )
\r
118 #define portPRIGROUP_SHIFT ( 8UL )
\r
120 /* Constants required to manipulate the VFP. */
\r
121 #define portFPCCR ( ( volatile unsigned long * ) 0xe000ef34 ) /* Floating point context control register. */
\r
122 #define portASPEN_AND_LSPEN_BITS ( 0x3UL << 30UL )
\r
124 /* Constants required to set up the initial stack. */
\r
125 #define portINITIAL_XPSR ( 0x01000000 )
\r
126 #define portINITIAL_EXEC_RETURN ( 0xfffffffd )
\r
128 /* Constants used with memory barrier intrinsics. */
\r
129 #define portSY_FULL_READ_WRITE ( 15 )
\r
131 /* The systick is a 24-bit counter. */
\r
132 #define portMAX_24_BIT_NUMBER ( 0xffffffUL )
\r
134 /* A fiddle factor to estimate the number of SysTick counts that would have
\r
135 occurred while the SysTick counter is stopped during tickless idle
\r
137 #define portMISSED_COUNTS_FACTOR ( 45UL )
\r
139 /* Each task maintains its own interrupt status in the critical nesting
\r
141 static unsigned portBASE_TYPE uxCriticalNesting = 0xaaaaaaaa;
\r
144 * Setup the timer to generate the tick interrupts. The implementation in this
\r
145 * file is weak to allow application writers to change the timer used to
\r
146 * generate the tick interrupt.
\r
148 void vPortSetupTimerInterrupt( void );
\r
151 * Exception handlers.
\r
153 void xPortPendSVHandler( void );
\r
154 void xPortSysTickHandler( void );
\r
155 void vPortSVCHandler( void );
\r
158 * Start first task is a separate function so it can be tested in isolation.
\r
160 static void prvStartFirstTask( void );
\r
163 * Functions defined in portasm.s to enable the VFP.
\r
165 static void prvEnableVFP( void );
\r
166 /*-----------------------------------------------------------*/
\r
169 * The number of SysTick increments that make up one tick period.
\r
171 #if configUSE_TICKLESS_IDLE == 1
\r
172 static unsigned long ulTimerCountsForOneTick = 0;
\r
173 #endif /* configUSE_TICKLESS_IDLE */
\r
176 * The maximum number of tick periods that can be suppressed is limited by the
\r
177 * 24 bit resolution of the SysTick timer.
\r
179 #if configUSE_TICKLESS_IDLE == 1
\r
180 static unsigned long xMaximumPossibleSuppressedTicks = 0;
\r
181 #endif /* configUSE_TICKLESS_IDLE */
\r
184 * Compensate for the CPU cycles that pass while the SysTick is stopped (low
\r
185 * power functionality only.
\r
187 #if configUSE_TICKLESS_IDLE == 1
\r
188 static unsigned long ulStoppedTimerCompensation = 0;
\r
189 #endif /* configUSE_TICKLESS_IDLE */
\r
192 * Used by the portASSERT_IF_INTERRUPT_PRIORITY_INVALID() macro to ensure
\r
193 * FreeRTOS API functions are not called from interrupts that have been assigned
\r
194 * a priority above configMAX_SYSCALL_INTERRUPT_PRIORITY.
\r
196 #if ( configASSERT_DEFINED == 1 )
\r
197 static unsigned char ucMaxSysCallPriority = 0;
\r
198 static unsigned long ulMaxPRIGROUPValue = 0;
\r
199 static const volatile unsigned char * const pcInterruptPriorityRegisters = ( unsigned char * ) portNVIC_IP_REGISTERS_OFFSET_16;
\r
200 #endif /* configASSERT_DEFINED */
\r
202 /*-----------------------------------------------------------*/
\r
205 * See header file for description.
\r
207 portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters )
\r
209 /* Simulate the stack frame as it would be created by a context switch
\r
212 /* Offset added to account for the way the MCU uses the stack on entry/exit
\r
213 of interrupts, and to ensure alignment. */
\r
216 *pxTopOfStack = portINITIAL_XPSR; /* xPSR */
\r
218 *pxTopOfStack = ( portSTACK_TYPE ) pxCode; /* PC */
\r
220 *pxTopOfStack = 0; /* LR */
\r
222 /* Save code space by skipping register initialisation. */
\r
223 pxTopOfStack -= 5; /* R12, R3, R2 and R1. */
\r
224 *pxTopOfStack = ( portSTACK_TYPE ) pvParameters; /* R0 */
\r
226 /* A save method is being used that requires each task to maintain its
\r
227 own exec return value. */
\r
229 *pxTopOfStack = portINITIAL_EXEC_RETURN;
\r
231 pxTopOfStack -= 8; /* R11, R10, R9, R8, R7, R6, R5 and R4. */
\r
233 return pxTopOfStack;
\r
235 /*-----------------------------------------------------------*/
\r
237 __asm void vPortSVCHandler( void )
\r
241 /* Get the location of the current TCB. */
\r
242 ldr r3, =pxCurrentTCB
\r
245 /* Pop the core registers. */
\r
246 ldmia r0!, {r4-r11, r14}
\r
252 /*-----------------------------------------------------------*/
\r
254 __asm void prvStartFirstTask( void )
\r
258 /* Use the NVIC offset register to locate the stack. */
\r
259 ldr r0, =0xE000ED08
\r
262 /* Set the msp back to the start of the stack. */
\r
264 /* Globally enable interrupts. */
\r
266 /* Call SVC to start the first task. */
\r
270 /*-----------------------------------------------------------*/
\r
272 __asm void prvEnableVFP( void )
\r
276 /* The FPU enable bits are in the CPACR. */
\r
277 ldr.w r0, =0xE000ED88
\r
280 /* Enable CP10 and CP11 coprocessors, then save back. */
\r
281 orr r1, r1, #( 0xf << 20 )
\r
286 /*-----------------------------------------------------------*/
\r
289 * See header file for description.
\r
291 portBASE_TYPE xPortStartScheduler( void )
\r
293 #if( configASSERT_DEFINED == 1 )
\r
295 volatile unsigned long ulOriginalPriority;
\r
296 volatile char * const pcFirstUserPriorityRegister = ( char * ) ( portNVIC_IP_REGISTERS_OFFSET_16 + portFIRST_USER_INTERRUPT_NUMBER );
\r
297 volatile unsigned char ucMaxPriorityValue;
\r
299 /* Determine the maximum priority from which ISR safe FreeRTOS API
\r
300 functions can be called. ISR safe functions are those that end in
\r
301 "FromISR". FreeRTOS maintains separate thread and ISR API functions to
\r
302 ensure interrupt entry is as fast and simple as possible.
\r
304 Save the interrupt priority value that is about to be clobbered. */
\r
305 ulOriginalPriority = *pcFirstUserPriorityRegister;
\r
307 /* Determine the number of priority bits available. First write to all
\r
309 *pcFirstUserPriorityRegister = portMAX_8_BIT_VALUE;
\r
311 /* Read the value back to see how many bits stuck. */
\r
312 ucMaxPriorityValue = *pcFirstUserPriorityRegister;
\r
314 /* Use the same mask on the maximum system call priority. */
\r
315 ucMaxSysCallPriority = configMAX_SYSCALL_INTERRUPT_PRIORITY & ucMaxPriorityValue;
\r
317 /* Calculate the maximum acceptable priority group value for the number
\r
318 of bits read back. */
\r
319 ulMaxPRIGROUPValue = portMAX_PRIGROUP_BITS;
\r
320 while( ( ucMaxPriorityValue & portTOP_BIT_OF_BYTE ) == portTOP_BIT_OF_BYTE )
\r
322 ulMaxPRIGROUPValue--;
\r
323 ucMaxPriorityValue <<= ( unsigned char ) 0x01;
\r
326 /* Shift the priority group value back to its position within the AIRCR
\r
328 ulMaxPRIGROUPValue <<= portPRIGROUP_SHIFT;
\r
329 ulMaxPRIGROUPValue &= portPRIORITY_GROUP_MASK;
\r
331 /* Restore the clobbered interrupt priority register to its original
\r
333 *pcFirstUserPriorityRegister = ulOriginalPriority;
\r
335 #endif /* conifgASSERT_DEFINED */
\r
337 /* Make PendSV and SysTick the lowest priority interrupts. */
\r
338 portNVIC_SYSPRI2_REG |= portNVIC_PENDSV_PRI;
\r
339 portNVIC_SYSPRI2_REG |= portNVIC_SYSTICK_PRI;
\r
341 /* Start the timer that generates the tick ISR. Interrupts are disabled
\r
343 vPortSetupTimerInterrupt();
\r
345 /* Initialise the critical nesting count ready for the first task. */
\r
346 uxCriticalNesting = 0;
\r
348 /* Ensure the VFP is enabled - it should be anyway. */
\r
351 /* Lazy save always. */
\r
352 *( portFPCCR ) |= portASPEN_AND_LSPEN_BITS;
\r
354 /* Start the first task. */
\r
355 prvStartFirstTask();
\r
357 /* Should not get here! */
\r
360 /*-----------------------------------------------------------*/
\r
362 void vPortEndScheduler( void )
\r
364 /* It is unlikely that the CM4F port will require this function as there
\r
365 is nothing to return to. */
\r
367 /*-----------------------------------------------------------*/
\r
369 void vPortYield( void )
\r
371 /* Set a PendSV to request a context switch. */
\r
372 portNVIC_INT_CTRL_REG = portNVIC_PENDSVSET_BIT;
\r
374 /* Barriers are normally not required but do ensure the code is completely
\r
375 within the specified behaviour for the architecture. */
\r
376 __dsb( portSY_FULL_READ_WRITE );
\r
377 __isb( portSY_FULL_READ_WRITE );
\r
379 /*-----------------------------------------------------------*/
\r
381 void vPortEnterCritical( void )
\r
383 portDISABLE_INTERRUPTS();
\r
384 uxCriticalNesting++;
\r
385 __dsb( portSY_FULL_READ_WRITE );
\r
386 __isb( portSY_FULL_READ_WRITE );
\r
388 /*-----------------------------------------------------------*/
\r
390 void vPortExitCritical( void )
\r
392 uxCriticalNesting--;
\r
393 if( uxCriticalNesting == 0 )
\r
395 portENABLE_INTERRUPTS();
\r
398 /*-----------------------------------------------------------*/
\r
400 __asm void xPortPendSVHandler( void )
\r
402 extern uxCriticalNesting;
\r
403 extern pxCurrentTCB;
\r
404 extern vTaskSwitchContext;
\r
410 /* Get the location of the current TCB. */
\r
411 ldr r3, =pxCurrentTCB
\r
414 /* Is the task using the FPU context? If so, push high vfp registers. */
\r
417 vstmdbeq r0!, {s16-s31}
\r
419 /* Save the core registers. */
\r
420 stmdb r0!, {r4-r11, r14}
\r
422 /* Save the new top of stack into the first member of the TCB. */
\r
425 stmdb sp!, {r3, r14}
\r
426 mov r0, #configMAX_SYSCALL_INTERRUPT_PRIORITY
\r
428 bl vTaskSwitchContext
\r
431 ldmia sp!, {r3, r14}
\r
433 /* The first item in pxCurrentTCB is the task top of stack. */
\r
437 /* Pop the core registers. */
\r
438 ldmia r0!, {r4-r11, r14}
\r
440 /* Is the task using the FPU context? If so, pop the high vfp registers
\r
444 vldmiaeq r0!, {s16-s31}
\r
450 /*-----------------------------------------------------------*/
\r
452 void xPortSysTickHandler( void )
\r
454 /* The SysTick runs at the lowest interrupt priority, so when this interrupt
\r
455 executes all interrupts must be unmasked. There is therefore no need to
\r
456 save and then restore the interrupt mask value as its value is already
\r
458 ( void ) portSET_INTERRUPT_MASK_FROM_ISR();
\r
460 /* Increment the RTOS tick. */
\r
461 if( xTaskIncrementTick() != pdFALSE )
\r
463 /* A context switch is required. Context switching is performed in
\r
464 the PendSV interrupt. Pend the PendSV interrupt. */
\r
465 portNVIC_INT_CTRL_REG = portNVIC_PENDSVSET_BIT;
\r
468 portCLEAR_INTERRUPT_MASK_FROM_ISR( 0 );
\r
470 /*-----------------------------------------------------------*/
\r
472 #if configUSE_TICKLESS_IDLE == 1
\r
474 __weak void vPortSuppressTicksAndSleep( portTickType xExpectedIdleTime )
\r
476 unsigned long ulReloadValue, ulCompleteTickPeriods, ulCompletedSysTickDecrements;
\r
477 portTickType xModifiableIdleTime;
\r
479 /* Make sure the SysTick reload value does not overflow the counter. */
\r
480 if( xExpectedIdleTime > xMaximumPossibleSuppressedTicks )
\r
482 xExpectedIdleTime = xMaximumPossibleSuppressedTicks;
\r
485 /* Stop the SysTick momentarily. The time the SysTick is stopped for
\r
486 is accounted for as best it can be, but using the tickless mode will
\r
487 inevitably result in some tiny drift of the time maintained by the
\r
488 kernel with respect to calendar time. */
\r
489 portNVIC_SYSTICK_CTRL_REG = portNVIC_SYSTICK_CLK_BIT | portNVIC_SYSTICK_INT_BIT;
\r
491 /* Calculate the reload value required to wait xExpectedIdleTime
\r
492 tick periods. -1 is used because this code will execute part way
\r
493 through one of the tick periods. */
\r
494 ulReloadValue = portNVIC_SYSTICK_CURRENT_VALUE_REG + ( ulTimerCountsForOneTick * ( xExpectedIdleTime - 1UL ) );
\r
495 if( ulReloadValue > ulStoppedTimerCompensation )
\r
497 ulReloadValue -= ulStoppedTimerCompensation;
\r
500 /* Enter a critical section but don't use the taskENTER_CRITICAL()
\r
501 method as that will mask interrupts that should exit sleep mode. */
\r
504 /* If a context switch is pending or a task is waiting for the scheduler
\r
505 to be unsuspended then abandon the low power entry. */
\r
506 if( eTaskConfirmSleepModeStatus() == eAbortSleep )
\r
508 /* Restart SysTick. */
\r
509 portNVIC_SYSTICK_CTRL_REG = portNVIC_SYSTICK_CLK_BIT | portNVIC_SYSTICK_INT_BIT | portNVIC_SYSTICK_ENABLE_BIT;
\r
511 /* Re-enable interrupts - see comments above __disable_irq() call
\r
517 /* Set the new reload value. */
\r
518 portNVIC_SYSTICK_LOAD_REG = ulReloadValue;
\r
520 /* Clear the SysTick count flag and set the count value back to
\r
522 portNVIC_SYSTICK_CURRENT_VALUE_REG = 0UL;
\r
524 /* Restart SysTick. */
\r
525 portNVIC_SYSTICK_CTRL_REG = portNVIC_SYSTICK_CLK_BIT | portNVIC_SYSTICK_INT_BIT | portNVIC_SYSTICK_ENABLE_BIT;
\r
527 /* Sleep until something happens. configPRE_SLEEP_PROCESSING() can
\r
528 set its parameter to 0 to indicate that its implementation contains
\r
529 its own wait for interrupt or wait for event instruction, and so wfi
\r
530 should not be executed again. However, the original expected idle
\r
531 time variable must remain unmodified, so a copy is taken. */
\r
532 xModifiableIdleTime = xExpectedIdleTime;
\r
533 configPRE_SLEEP_PROCESSING( xModifiableIdleTime );
\r
534 if( xModifiableIdleTime > 0 )
\r
536 __dsb( portSY_FULL_READ_WRITE );
\r
538 __isb( portSY_FULL_READ_WRITE );
\r
540 configPOST_SLEEP_PROCESSING( xExpectedIdleTime );
\r
542 /* Stop SysTick. Again, the time the SysTick is stopped for is
\r
543 accounted for as best it can be, but using the tickless mode will
\r
544 inevitably result in some tiny drift of the time maintained by the
\r
545 kernel with respect to calendar time. */
\r
546 portNVIC_SYSTICK_CTRL_REG = portNVIC_SYSTICK_CLK_BIT | portNVIC_SYSTICK_INT_BIT;
\r
548 /* Re-enable interrupts - see comments above __disable_irq() call
\r
552 if( ( portNVIC_SYSTICK_CTRL_REG & portNVIC_SYSTICK_COUNT_FLAG_BIT ) != 0 )
\r
554 /* The tick interrupt has already executed, and the SysTick
\r
555 count reloaded with ulReloadValue. Reset the
\r
556 portNVIC_SYSTICK_LOAD_REG with whatever remains of this tick
\r
558 portNVIC_SYSTICK_LOAD_REG = ( ulTimerCountsForOneTick - 1UL ) - ( ulReloadValue - portNVIC_SYSTICK_CURRENT_VALUE_REG );
\r
560 /* The tick interrupt handler will already have pended the tick
\r
561 processing in the kernel. As the pending tick will be
\r
562 processed as soon as this function exits, the tick value
\r
563 maintained by the tick is stepped forward by one less than the
\r
564 time spent waiting. */
\r
565 ulCompleteTickPeriods = xExpectedIdleTime - 1UL;
\r
569 /* Something other than the tick interrupt ended the sleep.
\r
570 Work out how long the sleep lasted rounded to complete tick
\r
571 periods (not the ulReload value which accounted for part
\r
573 ulCompletedSysTickDecrements = ( xExpectedIdleTime * ulTimerCountsForOneTick ) - portNVIC_SYSTICK_CURRENT_VALUE_REG;
\r
575 /* How many complete tick periods passed while the processor
\r
577 ulCompleteTickPeriods = ulCompletedSysTickDecrements / ulTimerCountsForOneTick;
\r
579 /* The reload value is set to whatever fraction of a single tick
\r
581 portNVIC_SYSTICK_LOAD_REG = ( ( ulCompleteTickPeriods + 1 ) * ulTimerCountsForOneTick ) - ulCompletedSysTickDecrements;
\r
584 /* Restart SysTick so it runs from portNVIC_SYSTICK_LOAD_REG
\r
585 again, then set portNVIC_SYSTICK_LOAD_REG back to its standard
\r
587 portNVIC_SYSTICK_CURRENT_VALUE_REG = 0UL;
\r
588 portNVIC_SYSTICK_CTRL_REG = portNVIC_SYSTICK_CLK_BIT | portNVIC_SYSTICK_INT_BIT | portNVIC_SYSTICK_ENABLE_BIT;
\r
590 vTaskStepTick( ulCompleteTickPeriods );
\r
592 /* The counter must start by the time the reload value is reset. */
\r
593 configASSERT( portNVIC_SYSTICK_CURRENT_VALUE_REG );
\r
594 portNVIC_SYSTICK_LOAD_REG = ulTimerCountsForOneTick - 1UL;
\r
598 #endif /* #if configUSE_TICKLESS_IDLE */
\r
600 /*-----------------------------------------------------------*/
\r
603 * Setup the SysTick timer to generate the tick interrupts at the required
\r
606 #if configOVERRIDE_DEFAULT_TICK_CONFIGURATION == 0
\r
608 void vPortSetupTimerInterrupt( void )
\r
610 /* Calculate the constants required to configure the tick interrupt. */
\r
611 #if configUSE_TICKLESS_IDLE == 1
\r
613 ulTimerCountsForOneTick = ( configSYSTICK_CLOCK_HZ / configTICK_RATE_HZ );
\r
614 xMaximumPossibleSuppressedTicks = portMAX_24_BIT_NUMBER / ulTimerCountsForOneTick;
\r
615 ulStoppedTimerCompensation = portMISSED_COUNTS_FACTOR / ( configCPU_CLOCK_HZ / configSYSTICK_CLOCK_HZ );
\r
617 #endif /* configUSE_TICKLESS_IDLE */
\r
619 /* Configure SysTick to interrupt at the requested rate. */
\r
620 portNVIC_SYSTICK_LOAD_REG = ( configSYSTICK_CLOCK_HZ / configTICK_RATE_HZ ) - 1UL;;
\r
621 portNVIC_SYSTICK_CTRL_REG = portNVIC_SYSTICK_CLK_BIT | portNVIC_SYSTICK_INT_BIT | portNVIC_SYSTICK_ENABLE_BIT;
\r
624 #endif /* configOVERRIDE_DEFAULT_TICK_CONFIGURATION */
\r
625 /*-----------------------------------------------------------*/
\r
627 __asm unsigned long ulPortSetInterruptMask( void )
\r
632 mov r1, #configMAX_SYSCALL_INTERRUPT_PRIORITY
\r
636 /*-----------------------------------------------------------*/
\r
638 __asm void vPortClearInterruptMask( unsigned long ulNewMask )
\r
645 /*-----------------------------------------------------------*/
\r
647 __asm unsigned long vPortGetIPSR( void )
\r
654 /*-----------------------------------------------------------*/
\r
656 #if( configASSERT_DEFINED == 1 )
\r
658 void vPortValidateInterruptPriority( void )
\r
660 unsigned long ulCurrentInterrupt;
\r
661 unsigned char ucCurrentPriority;
\r
663 /* Obtain the number of the currently executing interrupt. */
\r
664 ulCurrentInterrupt = vPortGetIPSR();
\r
666 /* Is the interrupt number a user defined interrupt? */
\r
667 if( ulCurrentInterrupt >= portFIRST_USER_INTERRUPT_NUMBER )
\r
669 /* Look up the interrupt's priority. */
\r
670 ucCurrentPriority = pcInterruptPriorityRegisters[ ulCurrentInterrupt ];
\r
672 /* The following assertion will fail if a service routine (ISR) for
\r
673 an interrupt that has been assigned a priority above
\r
674 configMAX_SYSCALL_INTERRUPT_PRIORITY calls an ISR safe FreeRTOS API
\r
675 function. ISR safe FreeRTOS API functions must *only* be called
\r
676 from interrupts that have been assigned a priority at or below
\r
677 configMAX_SYSCALL_INTERRUPT_PRIORITY.
\r
679 Numerically low interrupt priority numbers represent logically high
\r
680 interrupt priorities, therefore the priority of the interrupt must
\r
681 be set to a value equal to or numerically *higher* than
\r
682 configMAX_SYSCALL_INTERRUPT_PRIORITY.
\r
684 Interrupts that use the FreeRTOS API must not be left at their
\r
685 default priority of zero as that is the highest possible priority,
\r
686 which is guaranteed to be above configMAX_SYSCALL_INTERRUPT_PRIORITY,
\r
687 and therefore also guaranteed to be invalid.
\r
689 FreeRTOS maintains separate thread and ISR API functions to ensure
\r
690 interrupt entry is as fast and simple as possible.
\r
692 The following links provide detailed information:
\r
693 http://www.freertos.org/RTOS-Cortex-M3-M4.html
\r
694 http://www.freertos.org/FAQHelp.html */
\r
695 configASSERT( ucCurrentPriority >= ucMaxSysCallPriority );
\r
698 /* Priority grouping: The interrupt controller (NVIC) allows the bits
\r
699 that define each interrupt's priority to be split between bits that
\r
700 define the interrupt's pre-emption priority bits and bits that define
\r
701 the interrupt's sub-priority. For simplicity all bits must be defined
\r
702 to be pre-emption priority bits. The following assertion will fail if
\r
703 this is not the case (if some bits represent a sub-priority).
\r
705 If the application only uses CMSIS libraries for interrupt
\r
706 configuration then the correct setting can be achieved on all Cortex-M
\r
707 devices by calling NVIC_SetPriorityGrouping( 0 ); before starting the
\r
708 scheduler. Note however that some vendor specific peripheral libraries
\r
709 assume a non-zero priority group setting, in which cases using a value
\r
710 of zero will result in unpredicable behaviour. */
\r
711 configASSERT( ( portAIRCR_REG & portPRIORITY_GROUP_MASK ) <= ulMaxPRIGROUPValue );
\r
714 #endif /* configASSERT_DEFINED */
\r