port.c
Go to the documentation of this file.
1 /*
2  * FreeRTOS Kernel V10.0.0
3  * Copyright (C) 2017 Amazon.com, Inc. or its affiliates. All Rights Reserved.
4  *
5  * Permission is hereby granted, free of charge, to any person obtaining a copy of
6  * this software and associated documentation files (the "Software"), to deal in
7  * the Software without restriction, including without limitation the rights to
8  * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
9  * the Software, and to permit persons to whom the Software is furnished to do so,
10  * subject to the following conditions:
11  *
12  * The above copyright notice and this permission notice shall be included in all
13  * copies or substantial portions of the Software. If you wish to use our Amazon
14  * FreeRTOS name, please do so in a fair use way that does not cause confusion.
15  *
16  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
17  * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
18  * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
19  * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
20  * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
21  * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
22  *
23  * http://www.FreeRTOS.org
24  * http://aws.amazon.com/freertos
25  *
26  * 1 tab == 4 spaces!
27  */
28 
29 /*-----------------------------------------------------------
30  * Implementation of functions defined in portable.h for the ARM CM4F port.
31  *----------------------------------------------------------*/
32 
33 /* Scheduler includes. */
34 #include "FreeRTOS.h"
35 #include "task.h"
36 
37 #ifndef __VFP_FP__
38  #error This port can only be used when the project options are configured to enable hardware floating point support.
39 #endif
40 
41 #ifndef configSYSTICK_CLOCK_HZ
42  #define configSYSTICK_CLOCK_HZ configCPU_CLOCK_HZ
43  /* Ensure the SysTick is clocked at the same frequency as the core. */
44  #define portNVIC_SYSTICK_CLK_BIT ( 1UL << 2UL )
45 #else
46  /* The way the SysTick is clocked is not modified in case it is not the same
47  as the core. */
48  #define portNVIC_SYSTICK_CLK_BIT ( 0 )
49 #endif
50 
51 /* Constants required to manipulate the core. Registers first... */
52 #define portNVIC_SYSTICK_CTRL_REG ( * ( ( volatile uint32_t * ) 0xe000e010 ) )
53 #define portNVIC_SYSTICK_LOAD_REG ( * ( ( volatile uint32_t * ) 0xe000e014 ) )
54 #define portNVIC_SYSTICK_CURRENT_VALUE_REG ( * ( ( volatile uint32_t * ) 0xe000e018 ) )
55 #define portNVIC_SYSPRI2_REG ( * ( ( volatile uint32_t * ) 0xe000ed20 ) )
56 /* ...then bits in the registers. */
57 #define portNVIC_SYSTICK_INT_BIT ( 1UL << 1UL )
58 #define portNVIC_SYSTICK_ENABLE_BIT ( 1UL << 0UL )
59 #define portNVIC_SYSTICK_COUNT_FLAG_BIT ( 1UL << 16UL )
60 #define portNVIC_PENDSVCLEAR_BIT ( 1UL << 27UL )
61 #define portNVIC_PEND_SYSTICK_CLEAR_BIT ( 1UL << 25UL )
62 
63 #define portNVIC_PENDSV_PRI ( ( ( uint32_t ) configKERNEL_INTERRUPT_PRIORITY ) << 16UL )
64 #define portNVIC_SYSTICK_PRI ( ( ( uint32_t ) configKERNEL_INTERRUPT_PRIORITY ) << 24UL )
65 
66 /* Constants required to check the validity of an interrupt priority. */
67 #define portFIRST_USER_INTERRUPT_NUMBER ( 16 )
68 #define portNVIC_IP_REGISTERS_OFFSET_16 ( 0xE000E3F0 )
69 #define portAIRCR_REG ( * ( ( volatile uint32_t * ) 0xE000ED0C ) )
70 #define portMAX_8_BIT_VALUE ( ( uint8_t ) 0xff )
71 #define portTOP_BIT_OF_BYTE ( ( uint8_t ) 0x80 )
72 #define portMAX_PRIGROUP_BITS ( ( uint8_t ) 7 )
73 #define portPRIORITY_GROUP_MASK ( 0x07UL << 8UL )
74 #define portPRIGROUP_SHIFT ( 8UL )
75 
76 /* Masks off all bits but the VECTACTIVE bits in the ICSR register. */
77 #define portVECTACTIVE_MASK ( 0xFFUL )
78 
79 /* Constants required to manipulate the VFP. */
80 #define portFPCCR ( ( volatile uint32_t * ) 0xe000ef34 ) /* Floating point context control register. */
81 #define portASPEN_AND_LSPEN_BITS ( 0x3UL << 30UL )
82 
83 /* Constants required to set up the initial stack. */
84 #define portINITIAL_XPSR ( 0x01000000 )
85 #define portINITIAL_EXC_RETURN ( 0xfffffffd )
86 
87 /* The systick is a 24-bit counter. */
88 #define portMAX_24_BIT_NUMBER ( 0xffffffUL )
89 
90 /* For strict compliance with the Cortex-M spec the task start address should
91 have bit-0 clear, as it is loaded into the PC on exit from an ISR. */
92 #define portSTART_ADDRESS_MASK ( ( StackType_t ) 0xfffffffeUL )
93 
94 /* A fiddle factor to estimate the number of SysTick counts that would have
95 occurred while the SysTick counter is stopped during tickless idle
96 calculations. */
97 #define portMISSED_COUNTS_FACTOR ( 45UL )
98 
99 /* Let the user override the pre-loading of the initial LR with the address of
100 prvTaskExitError() in case it messes up unwinding of the stack in the
101 debugger. */
102 #ifdef configTASK_RETURN_ADDRESS
103  #define portTASK_RETURN_ADDRESS configTASK_RETURN_ADDRESS
104 #else
105  #define portTASK_RETURN_ADDRESS prvTaskExitError
106 #endif
107 
108 /*
109  * Setup the timer to generate the tick interrupts. The implementation in this
110  * file is weak to allow application writers to change the timer used to
111  * generate the tick interrupt.
112  */
113 void vPortSetupTimerInterrupt( void );
114 
115 /*
116  * Exception handlers.
117  */
118 void xPortPendSVHandler( void ) __attribute__ (( naked ));
119 void xPortSysTickHandler( void );
120 void vPortSVCHandler( void ) __attribute__ (( naked ));
121 
122 /*
123  * Start first task is a separate function so it can be tested in isolation.
124  */
125 static void prvPortStartFirstTask( void ) __attribute__ (( naked ));
126 
127 /*
128  * Function to enable the VFP.
129  */
130 static void vPortEnableVFP( void ) __attribute__ (( naked ));
131 
132 /*
133  * Used to catch tasks that attempt to return from their implementing function.
134  */
135 static void prvTaskExitError( void );
136 
137 /*-----------------------------------------------------------*/
138 
139 /* Each task maintains its own interrupt status in the critical nesting
140 variable. */
141 static UBaseType_t uxCriticalNesting = 0xaaaaaaaa;
142 
143 /*
144  * The number of SysTick increments that make up one tick period.
145  */
146 #if( configUSE_TICKLESS_IDLE == 1 )
147  static uint32_t ulTimerCountsForOneTick = 0;
148 #endif /* configUSE_TICKLESS_IDLE */
149 
150 /*
151  * The maximum number of tick periods that can be suppressed is limited by the
152  * 24 bit resolution of the SysTick timer.
153  */
154 #if( configUSE_TICKLESS_IDLE == 1 )
155  static uint32_t xMaximumPossibleSuppressedTicks = 0;
156 #endif /* configUSE_TICKLESS_IDLE */
157 
158 /*
159  * Compensate for the CPU cycles that pass while the SysTick is stopped (low
160  * power functionality only.
161  */
162 #if( configUSE_TICKLESS_IDLE == 1 )
163  static uint32_t ulStoppedTimerCompensation = 0;
164 #endif /* configUSE_TICKLESS_IDLE */
165 
166 /*
167  * Used by the portASSERT_IF_INTERRUPT_PRIORITY_INVALID() macro to ensure
168  * FreeRTOS API functions are not called from interrupts that have been assigned
169  * a priority above configMAX_SYSCALL_INTERRUPT_PRIORITY.
170  */
171 #if( configASSERT_DEFINED == 1 )
172  static uint8_t ucMaxSysCallPriority = 0;
173  static uint32_t ulMaxPRIGROUPValue = 0;
174  static const volatile uint8_t * const pcInterruptPriorityRegisters = ( const volatile uint8_t * const ) portNVIC_IP_REGISTERS_OFFSET_16;
175 #endif /* configASSERT_DEFINED */
176 
177 /*-----------------------------------------------------------*/
178 
179 /*
180  * See header file for description.
181  */
182 StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters )
183 {
184  /* Simulate the stack frame as it would be created by a context switch
185  interrupt. */
186 
187  /* Offset added to account for the way the MCU uses the stack on entry/exit
188  of interrupts, and to ensure alignment. */
189  pxTopOfStack--;
190 
191  *pxTopOfStack = portINITIAL_XPSR; /* xPSR */
192  pxTopOfStack--;
193  *pxTopOfStack = ( ( StackType_t ) pxCode ) & portSTART_ADDRESS_MASK; /* PC */
194  pxTopOfStack--;
195  *pxTopOfStack = ( StackType_t ) portTASK_RETURN_ADDRESS; /* LR */
196 
197  /* Save code space by skipping register initialisation. */
198  pxTopOfStack -= 5; /* R12, R3, R2 and R1. */
199  *pxTopOfStack = ( StackType_t ) pvParameters; /* R0 */
200 
201  /* A save method is being used that requires each task to maintain its
202  own exec return value. */
203  pxTopOfStack--;
204  *pxTopOfStack = portINITIAL_EXC_RETURN;
205 
206  pxTopOfStack -= 8; /* R11, R10, R9, R8, R7, R6, R5 and R4. */
207 
208  return pxTopOfStack;
209 }
210 /*-----------------------------------------------------------*/
211 
212 static void prvTaskExitError( void )
213 {
214 volatile uint32_t ulDummy = 0;
215 
216  /* A function that implements a task must not exit or attempt to return to
217  its caller as there is nothing to return to. If a task wants to exit it
218  should instead call vTaskDelete( NULL ).
219 
220  Artificially force an assert() to be triggered if configASSERT() is
221  defined, then stop here so application writers can catch the error. */
222  configASSERT( uxCriticalNesting == ~0UL );
224  while( ulDummy == 0 )
225  {
226  /* This file calls prvTaskExitError() after the scheduler has been
227  started to remove a compiler warning about the function being defined
228  but never called. ulDummy is used purely to quieten other warnings
229  about code appearing after this function is called - making ulDummy
230  volatile makes the compiler think the function could return and
231  therefore not output an 'unreachable code' warning for code that appears
232  after it. */
233  }
234 }
235 /*-----------------------------------------------------------*/
236 
237 void vPortSVCHandler( void )
238 {
239  __asm volatile (
240  " ldr r3, pxCurrentTCBConst2 \n" /* Restore the context. */
241  " ldr r1, [r3] \n" /* Use pxCurrentTCBConst to get the pxCurrentTCB address. */
242  " ldr r0, [r1] \n" /* The first item in pxCurrentTCB is the task top of stack. */
243  " ldmia r0!, {r4-r11, r14} \n" /* Pop the registers that are not automatically saved on exception entry and the critical nesting count. */
244  " msr psp, r0 \n" /* Restore the task stack pointer. */
245  " isb \n"
246  " mov r0, #0 \n"
247  " msr basepri, r0 \n"
248  " bx r14 \n"
249  " \n"
250  " .align 4 \n"
251  "pxCurrentTCBConst2: .word pxCurrentTCB \n"
252  );
253 }
254 /*-----------------------------------------------------------*/
255 
256 static void prvPortStartFirstTask( void )
257 {
258  /* Start the first task. This also clears the bit that indicates the FPU is
259  in use in case the FPU was used before the scheduler was started - which
260  would otherwise result in the unnecessary leaving of space in the SVC stack
261  for lazy saving of FPU registers. */
262  __asm volatile(
263  " ldr r0, =0xE000ED08 \n" /* Use the NVIC offset register to locate the stack. */
264  " ldr r0, [r0] \n"
265  " ldr r0, [r0] \n"
266  " msr msp, r0 \n" /* Set the msp back to the start of the stack. */
267  " mov r0, #0 \n" /* Clear the bit that indicates the FPU is in use, see comment above. */
268  " msr control, r0 \n"
269  " cpsie i \n" /* Globally enable interrupts. */
270  " cpsie f \n"
271  " dsb \n"
272  " isb \n"
273  " svc 0 \n" /* System call to start first task. */
274  " nop \n"
275  );
276 }
277 /*-----------------------------------------------------------*/
278 
279 /*
280  * See header file for description.
281  */
283 {
284  /* configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to 0.
285  See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html */
287 
288  #if( configASSERT_DEFINED == 1 )
289  {
290  volatile uint32_t ulOriginalPriority;
291  volatile uint8_t * const pucFirstUserPriorityRegister = ( volatile uint8_t * const ) ( portNVIC_IP_REGISTERS_OFFSET_16 + portFIRST_USER_INTERRUPT_NUMBER );
292  volatile uint8_t ucMaxPriorityValue;
293 
294  /* Determine the maximum priority from which ISR safe FreeRTOS API
295  functions can be called. ISR safe functions are those that end in
296  "FromISR". FreeRTOS maintains separate thread and ISR API functions to
297  ensure interrupt entry is as fast and simple as possible.
298 
299  Save the interrupt priority value that is about to be clobbered. */
300  ulOriginalPriority = *pucFirstUserPriorityRegister;
301 
302  /* Determine the number of priority bits available. First write to all
303  possible bits. */
304  *pucFirstUserPriorityRegister = portMAX_8_BIT_VALUE;
305 
306  /* Read the value back to see how many bits stuck. */
307  ucMaxPriorityValue = *pucFirstUserPriorityRegister;
308 
309  /* Use the same mask on the maximum system call priority. */
310  ucMaxSysCallPriority = configMAX_SYSCALL_INTERRUPT_PRIORITY & ucMaxPriorityValue;
311 
312  /* Calculate the maximum acceptable priority group value for the number
313  of bits read back. */
314  ulMaxPRIGROUPValue = portMAX_PRIGROUP_BITS;
315  while( ( ucMaxPriorityValue & portTOP_BIT_OF_BYTE ) == portTOP_BIT_OF_BYTE )
316  {
317  ulMaxPRIGROUPValue--;
318  ucMaxPriorityValue <<= ( uint8_t ) 0x01;
319  }
320 
321  #ifdef __NVIC_PRIO_BITS
322  {
323  /* Check the CMSIS configuration that defines the number of
324  priority bits matches the number of priority bits actually queried
325  from the hardware. */
326  configASSERT( ( portMAX_PRIGROUP_BITS - ulMaxPRIGROUPValue ) == __NVIC_PRIO_BITS );
327  }
328  #endif
329 
330  #ifdef configPRIO_BITS
331  {
332  /* Check the FreeRTOS configuration that defines the number of
333  priority bits matches the number of priority bits actually queried
334  from the hardware. */
335  configASSERT( ( portMAX_PRIGROUP_BITS - ulMaxPRIGROUPValue ) == configPRIO_BITS );
336  }
337  #endif
338 
339  /* Shift the priority group value back to its position within the AIRCR
340  register. */
341  ulMaxPRIGROUPValue <<= portPRIGROUP_SHIFT;
342  ulMaxPRIGROUPValue &= portPRIORITY_GROUP_MASK;
343 
344  /* Restore the clobbered interrupt priority register to its original
345  value. */
346  *pucFirstUserPriorityRegister = ulOriginalPriority;
347  }
348  #endif /* conifgASSERT_DEFINED */
349 
350  /* Make PendSV and SysTick the lowest priority interrupts. */
353 
354  /* Start the timer that generates the tick ISR. Interrupts are disabled
355  here already. */
357 
358  /* Initialise the critical nesting count ready for the first task. */
359  uxCriticalNesting = 0;
360 
361  /* Ensure the VFP is enabled - it should be anyway. */
362  vPortEnableVFP();
363 
364  /* Lazy save always. */
366 
367  /* Start the first task. */
369 
370  /* Should never get here as the tasks will now be executing! Call the task
371  exit error function to prevent compiler warnings about a static function
372  not being called in the case that the application writer overrides this
373  functionality by defining configTASK_RETURN_ADDRESS. Call
374  vTaskSwitchContext() so link time optimisation does not remove the
375  symbol. */
378 
379  /* Should not get here! */
380  return 0;
381 }
382 /*-----------------------------------------------------------*/
383 
384 void vPortEndScheduler( void )
385 {
386  /* Not implemented in ports where there is nothing to return to.
387  Artificially force an assert. */
388  configASSERT( uxCriticalNesting == 1000UL );
389 }
390 /*-----------------------------------------------------------*/
391 
392 void vPortEnterCritical( void )
393 {
395  uxCriticalNesting++;
396 
397  /* This is not the interrupt safe version of the enter critical function so
398  assert() if it is being called from an interrupt context. Only API
399  functions that end in "FromISR" can be used in an interrupt. Only assert if
400  the critical nesting count is 1 to protect against recursive calls if the
401  assert function also uses a critical section. */
402  if( uxCriticalNesting == 1 )
403  {
405  }
406 }
407 /*-----------------------------------------------------------*/
408 
409 void vPortExitCritical( void )
410 {
411  configASSERT( uxCriticalNesting );
412  uxCriticalNesting--;
413  if( uxCriticalNesting == 0 )
414  {
416  }
417 }
418 /*-----------------------------------------------------------*/
419 
420 void xPortPendSVHandler( void )
421 {
422  /* This is a naked function. */
423 
424  __asm volatile
425  (
426  " mrs r0, psp \n"
427  " isb \n"
428  " \n"
429  " ldr r3, pxCurrentTCBConst \n" /* Get the location of the current TCB. */
430  " ldr r2, [r3] \n"
431  " \n"
432  " tst r14, #0x10 \n" /* Is the task using the FPU context? If so, push high vfp registers. */
433  " it eq \n"
434  " vstmdbeq r0!, {s16-s31} \n"
435  " \n"
436  " stmdb r0!, {r4-r11, r14} \n" /* Save the core registers. */
437  " str r0, [r2] \n" /* Save the new top of stack into the first member of the TCB. */
438  " \n"
439  " stmdb sp!, {r0, r3} \n"
440  " mov r0, %0 \n"
441  " cpsid i \n" /* Errata workaround. */
442  " msr basepri, r0 \n"
443  " dsb \n"
444  " isb \n"
445  " cpsie i \n" /* Errata workaround. */
446  " bl vTaskSwitchContext \n"
447  " mov r0, #0 \n"
448  " msr basepri, r0 \n"
449  " ldmia sp!, {r0, r3} \n"
450  " \n"
451  " ldr r1, [r3] \n" /* The first item in pxCurrentTCB is the task top of stack. */
452  " ldr r0, [r1] \n"
453  " \n"
454  " ldmia r0!, {r4-r11, r14} \n" /* Pop the core registers. */
455  " \n"
456  " tst r14, #0x10 \n" /* Is the task using the FPU context? If so, pop the high vfp registers too. */
457  " it eq \n"
458  " vldmiaeq r0!, {s16-s31} \n"
459  " \n"
460  " msr psp, r0 \n"
461  " isb \n"
462  " \n"
463  #ifdef WORKAROUND_PMU_CM001 /* XMC4000 specific errata workaround. */
464  #if WORKAROUND_PMU_CM001 == 1
465  " push { r14 } \n"
466  " pop { pc } \n"
467  #endif
468  #endif
469  " \n"
470  " bx r14 \n"
471  " \n"
472  " .align 4 \n"
473  "pxCurrentTCBConst: .word pxCurrentTCB \n"
475  );
476 }
477 /*-----------------------------------------------------------*/
478 
480 {
481  /* The SysTick runs at the lowest interrupt priority, so when this interrupt
482  executes all interrupts must be unmasked. There is therefore no need to
483  save and then restore the interrupt mask value as its value is already
484  known. */
486  {
487  /* Increment the RTOS tick. */
488  if( xTaskIncrementTick() != pdFALSE )
489  {
490  /* A context switch is required. Context switching is performed in
491  the PendSV interrupt. Pend the PendSV interrupt. */
493  }
494  }
496 }
497 /*-----------------------------------------------------------*/
498 
499 #if( configUSE_TICKLESS_IDLE == 1 )
500 
501  __attribute__((weak)) void vPortSuppressTicksAndSleep( TickType_t xExpectedIdleTime )
502  {
503  uint32_t ulReloadValue, ulCompleteTickPeriods, ulCompletedSysTickDecrements;
504  TickType_t xModifiableIdleTime;
505 
506  /* Make sure the SysTick reload value does not overflow the counter. */
507  if( xExpectedIdleTime > xMaximumPossibleSuppressedTicks )
508  {
509  xExpectedIdleTime = xMaximumPossibleSuppressedTicks;
510  }
511 
512  /* Stop the SysTick momentarily. The time the SysTick is stopped for
513  is accounted for as best it can be, but using the tickless mode will
514  inevitably result in some tiny drift of the time maintained by the
515  kernel with respect to calendar time. */
517 
518  /* Calculate the reload value required to wait xExpectedIdleTime
519  tick periods. -1 is used because this code will execute part way
520  through one of the tick periods. */
521  ulReloadValue = portNVIC_SYSTICK_CURRENT_VALUE_REG + ( ulTimerCountsForOneTick * ( xExpectedIdleTime - 1UL ) );
522  if( ulReloadValue > ulStoppedTimerCompensation )
523  {
524  ulReloadValue -= ulStoppedTimerCompensation;
525  }
526 
527  /* Enter a critical section but don't use the taskENTER_CRITICAL()
528  method as that will mask interrupts that should exit sleep mode. */
529  __asm volatile( "cpsid i" ::: "memory" );
530  __asm volatile( "dsb" );
531  __asm volatile( "isb" );
532 
533  /* If a context switch is pending or a task is waiting for the scheduler
534  to be unsuspended then abandon the low power entry. */
536  {
537  /* Restart from whatever is left in the count register to complete
538  this tick period. */
540 
541  /* Restart SysTick. */
543 
544  /* Reset the reload register to the value required for normal tick
545  periods. */
546  portNVIC_SYSTICK_LOAD_REG = ulTimerCountsForOneTick - 1UL;
547 
548  /* Re-enable interrupts - see comments above the cpsid instruction()
549  above. */
550  __asm volatile( "cpsie i" ::: "memory" );
551  }
552  else
553  {
554  /* Set the new reload value. */
555  portNVIC_SYSTICK_LOAD_REG = ulReloadValue;
556 
557  /* Clear the SysTick count flag and set the count value back to
558  zero. */
560 
561  /* Restart SysTick. */
563 
564  /* Sleep until something happens. configPRE_SLEEP_PROCESSING() can
565  set its parameter to 0 to indicate that its implementation contains
566  its own wait for interrupt or wait for event instruction, and so wfi
567  should not be executed again. However, the original expected idle
568  time variable must remain unmodified, so a copy is taken. */
569  xModifiableIdleTime = xExpectedIdleTime;
570  configPRE_SLEEP_PROCESSING( xModifiableIdleTime );
571  if( xModifiableIdleTime > 0 )
572  {
573  __asm volatile( "dsb" ::: "memory" );
574  __asm volatile( "wfi" );
575  __asm volatile( "isb" );
576  }
577  configPOST_SLEEP_PROCESSING( xExpectedIdleTime );
578 
579  /* Re-enable interrupts to allow the interrupt that brought the MCU
580  out of sleep mode to execute immediately. see comments above
581  __disable_interrupt() call above. */
582  __asm volatile( "cpsie i" ::: "memory" );
583  __asm volatile( "dsb" );
584  __asm volatile( "isb" );
585 
586  /* Disable interrupts again because the clock is about to be stopped
587  and interrupts that execute while the clock is stopped will increase
588  any slippage between the time maintained by the RTOS and calendar
589  time. */
590  __asm volatile( "cpsid i" ::: "memory" );
591  __asm volatile( "dsb" );
592  __asm volatile( "isb" );
593 
594  /* Disable the SysTick clock without reading the
595  portNVIC_SYSTICK_CTRL_REG register to ensure the
596  portNVIC_SYSTICK_COUNT_FLAG_BIT is not cleared if it is set. Again,
597  the time the SysTick is stopped for is accounted for as best it can
598  be, but using the tickless mode will inevitably result in some tiny
599  drift of the time maintained by the kernel with respect to calendar
600  time*/
602 
603  /* Determine if the SysTick clock has already counted to zero and
604  been set back to the current reload value (the reload back being
605  correct for the entire expected idle time) or if the SysTick is yet
606  to count to zero (in which case an interrupt other than the SysTick
607  must have brought the system out of sleep mode). */
608  if( ( portNVIC_SYSTICK_CTRL_REG & portNVIC_SYSTICK_COUNT_FLAG_BIT ) != 0 )
609  {
610  uint32_t ulCalculatedLoadValue;
611 
612  /* The tick interrupt is already pending, and the SysTick count
613  reloaded with ulReloadValue. Reset the
614  portNVIC_SYSTICK_LOAD_REG with whatever remains of this tick
615  period. */
616  ulCalculatedLoadValue = ( ulTimerCountsForOneTick - 1UL ) - ( ulReloadValue - portNVIC_SYSTICK_CURRENT_VALUE_REG );
617 
618  /* Don't allow a tiny value, or values that have somehow
619  underflowed because the post sleep hook did something
620  that took too long. */
621  if( ( ulCalculatedLoadValue < ulStoppedTimerCompensation ) || ( ulCalculatedLoadValue > ulTimerCountsForOneTick ) )
622  {
623  ulCalculatedLoadValue = ( ulTimerCountsForOneTick - 1UL );
624  }
625 
626  portNVIC_SYSTICK_LOAD_REG = ulCalculatedLoadValue;
627 
628  /* As the pending tick will be processed as soon as this
629  function exits, the tick value maintained by the tick is stepped
630  forward by one less than the time spent waiting. */
631  ulCompleteTickPeriods = xExpectedIdleTime - 1UL;
632  }
633  else
634  {
635  /* Something other than the tick interrupt ended the sleep.
636  Work out how long the sleep lasted rounded to complete tick
637  periods (not the ulReload value which accounted for part
638  ticks). */
639  ulCompletedSysTickDecrements = ( xExpectedIdleTime * ulTimerCountsForOneTick ) - portNVIC_SYSTICK_CURRENT_VALUE_REG;
640 
641  /* How many complete tick periods passed while the processor
642  was waiting? */
643  ulCompleteTickPeriods = ulCompletedSysTickDecrements / ulTimerCountsForOneTick;
644 
645  /* The reload value is set to whatever fraction of a single tick
646  period remains. */
647  portNVIC_SYSTICK_LOAD_REG = ( ( ulCompleteTickPeriods + 1UL ) * ulTimerCountsForOneTick ) - ulCompletedSysTickDecrements;
648  }
649 
650  /* Restart SysTick so it runs from portNVIC_SYSTICK_LOAD_REG
651  again, then set portNVIC_SYSTICK_LOAD_REG back to its standard
652  value. */
654  portNVIC_SYSTICK_CTRL_REG |= portNVIC_SYSTICK_ENABLE_BIT;
655  vTaskStepTick( ulCompleteTickPeriods );
656  portNVIC_SYSTICK_LOAD_REG = ulTimerCountsForOneTick - 1UL;
657 
658  /* Exit with interrpts enabled. */
659  __asm volatile( "cpsie i" ::: "memory" );
660  }
661  }
662 
663 #endif /* #if configUSE_TICKLESS_IDLE */
664 /*-----------------------------------------------------------*/
665 
666 /*
667  * Setup the systick timer to generate the tick interrupts at the required
668  * frequency.
669  */
671 {
672  /* Calculate the constants required to configure the tick interrupt. */
673  #if( configUSE_TICKLESS_IDLE == 1 )
674  {
675  ulTimerCountsForOneTick = ( configSYSTICK_CLOCK_HZ / configTICK_RATE_HZ );
676  xMaximumPossibleSuppressedTicks = portMAX_24_BIT_NUMBER / ulTimerCountsForOneTick;
677  ulStoppedTimerCompensation = portMISSED_COUNTS_FACTOR / ( configCPU_CLOCK_HZ / configSYSTICK_CLOCK_HZ );
678  }
679  #endif /* configUSE_TICKLESS_IDLE */
680 
681  /* Stop and clear the SysTick. */
684 
685  /* Configure SysTick to interrupt at the requested rate. */
688 }
689 /*-----------------------------------------------------------*/
690 
691 /* This is a naked function. */
692 static void vPortEnableVFP( void )
693 {
694  __asm volatile
695  (
696  " ldr.w r0, =0xE000ED88 \n" /* The FPU enable bits are in the CPACR. */
697  " ldr r1, [r0] \n"
698  " \n"
699  " orr r1, r1, #( 0xf << 20 ) \n" /* Enable CP10 and CP11 coprocessors, then save back. */
700  " str r1, [r0] \n"
701  " bx r14 "
702  );
703 }
704 /*-----------------------------------------------------------*/
705 
706 #if( configASSERT_DEFINED == 1 )
707 
708  void vPortValidateInterruptPriority( void )
709  {
710  uint32_t ulCurrentInterrupt;
711  uint8_t ucCurrentPriority;
712 
713  /* Obtain the number of the currently executing interrupt. */
714  __asm volatile( "mrs %0, ipsr" : "=r"( ulCurrentInterrupt ) :: "memory" );
715 
716  /* Is the interrupt number a user defined interrupt? */
717  if( ulCurrentInterrupt >= portFIRST_USER_INTERRUPT_NUMBER )
718  {
719  /* Look up the interrupt's priority. */
720  ucCurrentPriority = pcInterruptPriorityRegisters[ ulCurrentInterrupt ];
721 
722  /* The following assertion will fail if a service routine (ISR) for
723  an interrupt that has been assigned a priority above
724  configMAX_SYSCALL_INTERRUPT_PRIORITY calls an ISR safe FreeRTOS API
725  function. ISR safe FreeRTOS API functions must *only* be called
726  from interrupts that have been assigned a priority at or below
727  configMAX_SYSCALL_INTERRUPT_PRIORITY.
728 
729  Numerically low interrupt priority numbers represent logically high
730  interrupt priorities, therefore the priority of the interrupt must
731  be set to a value equal to or numerically *higher* than
732  configMAX_SYSCALL_INTERRUPT_PRIORITY.
733 
734  Interrupts that use the FreeRTOS API must not be left at their
735  default priority of zero as that is the highest possible priority,
736  which is guaranteed to be above configMAX_SYSCALL_INTERRUPT_PRIORITY,
737  and therefore also guaranteed to be invalid.
738 
739  FreeRTOS maintains separate thread and ISR API functions to ensure
740  interrupt entry is as fast and simple as possible.
741 
742  The following links provide detailed information:
743  http://www.freertos.org/RTOS-Cortex-M3-M4.html
744  http://www.freertos.org/FAQHelp.html */
745  configASSERT( ucCurrentPriority >= ucMaxSysCallPriority );
746  }
747 
748  /* Priority grouping: The interrupt controller (NVIC) allows the bits
749  that define each interrupt's priority to be split between bits that
750  define the interrupt's pre-emption priority bits and bits that define
751  the interrupt's sub-priority. For simplicity all bits must be defined
752  to be pre-emption priority bits. The following assertion will fail if
753  this is not the case (if some bits represent a sub-priority).
754 
755  If the application only uses CMSIS libraries for interrupt
756  configuration then the correct setting can be achieved on all Cortex-M
757  devices by calling NVIC_SetPriorityGrouping( 0 ); before starting the
758  scheduler. Note however that some vendor specific peripheral libraries
759  assume a non-zero priority group setting, in which cases using a value
760  of zero will result in unpredictable behaviour. */
761  configASSERT( ( portAIRCR_REG & portPRIORITY_GROUP_MASK ) <= ulMaxPRIGROUPValue );
762  }
763 
764 #endif /* configASSERT_DEFINED */
765 
766 
#define portNVIC_SYSTICK_CLK_BIT
Definition: port.c:44
BaseType_t xPortStartScheduler(void)
Definition: port.c:282
void vTaskSwitchContext(void) PRIVILEGED_FUNCTION
Definition: tasks.c:2853
#define configCPU_CLOCK_HZ
void xPortPendSVHandler(void xPortSysTickHandler void)
Definition: port.c:118
#define portMISSED_COUNTS_FACTOR
Definition: port.c:97
static void vPortEnableVFP(void)
Definition: port.c:692
void xPortSysTickHandler(void)
Definition: port.c:479
#define portINITIAL_EXC_RETURN
Definition: port.c:85
#define portENABLE_INTERRUPTS()
Definition: portmacro.h:103
#define portDISABLE_INTERRUPTS()
Definition: portmacro.h:102
#define configPRE_SLEEP_PROCESSING(x)
Definition: FreeRTOS.h:747
#define portPRIGROUP_SHIFT
Definition: port.c:74
__attribute__((weak))
Definition: port.c:670
#define portTOP_BIT_OF_BYTE
Definition: port.c:71
void vPortEnterCritical(void)
Definition: port.c:392
#define portNVIC_SYSPRI2_REG
Definition: port.c:55
void vPortSVCHandler(void)
Definition: port.c:237
unsigned long UBaseType_t
Definition: portmacro.h:58
void vPortEndScheduler(void)
Definition: port.c:384
#define portNVIC_SYSTICK_PRI
Definition: port.c:64
void vPortSuppressTicksAndSleep(TickType_t xExpectedIdleTime)
uint32_t TickType_t
Definition: portmacro.h:64
#define portINITIAL_XPSR
Definition: port.c:84
void vTaskStepTick(const TickType_t xTicksToJump) PRIVILEGED_FUNCTION
#define portPRIORITY_GROUP_MASK
Definition: port.c:73
StackType_t * pxPortInitialiseStack(StackType_t *pxTopOfStack, TaskFunction_t pxCode, void *pvParameters) PRIVILEGED_FUNCTION
#define portNVIC_PENDSV_PRI
Definition: port.c:63
#define configPOST_SLEEP_PROCESSING(x)
Definition: FreeRTOS.h:751
#define configASSERT(x)
Definition: FreeRTOS.h:235
#define __NVIC_PRIO_BITS
Definition: same70j19.h:293
#define portAIRCR_REG
Definition: port.c:69
#define portNVIC_SYSTICK_LOAD_REG
Definition: port.c:53
#define portNVIC_SYSTICK_CURRENT_VALUE_REG
Definition: port.c:54
#define portMAX_PRIGROUP_BITS
Definition: port.c:72
long BaseType_t
Definition: portmacro.h:57
#define portFPCCR
Definition: port.c:80
#define portFIRST_USER_INTERRUPT_NUMBER
Definition: port.c:67
#define portVECTACTIVE_MASK
Definition: port.c:77
#define portSTART_ADDRESS_MASK
Definition: port.c:92
#define configSYSTICK_CLOCK_HZ
Definition: port.c:42
#define portTASK_RETURN_ADDRESS
Definition: port.c:105
static void prvPortStartFirstTask(void)
Definition: port.c:256
#define pdFALSE
Definition: projdefs.h:45
BaseType_t xTaskIncrementTick(void) PRIVILEGED_FUNCTION
Definition: tasks.c:2591
#define portNVIC_SYSTICK_INT_BIT
Definition: port.c:57
void vPortSetupTimerInterrupt(void)
eSleepModeStatus eTaskConfirmSleepModeStatus(void) PRIVILEGED_FUNCTION
#define portNVIC_SYSTICK_COUNT_FLAG_BIT
Definition: port.c:59
static void prvTaskExitError(void)
Definition: port.c:212
#define portNVIC_SYSTICK_CTRL_REG
Definition: port.c:52
#define configMAX_SYSCALL_INTERRUPT_PRIORITY
#define configTICK_RATE_HZ
#define portNVIC_IP_REGISTERS_OFFSET_16
Definition: port.c:68
#define portMAX_8_BIT_VALUE
Definition: port.c:70
#define portNVIC_SYSTICK_ENABLE_BIT
Definition: port.c:58
#define portMAX_24_BIT_NUMBER
Definition: port.c:88
void(* TaskFunction_t)(void *)
Definition: projdefs.h:36
#define configPRIO_BITS
#define portASPEN_AND_LSPEN_BITS
Definition: port.c:81
portSTACK_TYPE StackType_t
Definition: portmacro.h:56
#define portNVIC_PENDSVSET_BIT
Definition: portmacro.h:92
#define portNVIC_INT_CTRL_REG
Definition: portmacro.h:91
void vPortExitCritical(void)
Definition: port.c:409


inertial_sense_ros
Author(s):
autogenerated on Sat Sep 19 2020 03:19:04