Macros | Functions
port.c File Reference
#include "FreeRTOS.h"
#include "task.h"
Include dependency graph for port.c:

Go to the source code of this file.

Macros

#define configSYSTICK_CLOCK_HZ   configCPU_CLOCK_HZ
 
#define portAIRCR_REG   ( * ( ( volatile uint32_t * ) 0xE000ED0C ) )
 
#define portASPEN_AND_LSPEN_BITS   ( 0x3UL << 30UL )
 
#define portFIRST_USER_INTERRUPT_NUMBER   ( 16 )
 
#define portFPCCR   ( ( volatile uint32_t * ) 0xe000ef34 ) /* Floating point context control register. */
 
#define portINITIAL_EXC_RETURN   ( 0xfffffffd )
 
#define portINITIAL_XPSR   ( 0x01000000 )
 
#define portMAX_24_BIT_NUMBER   ( 0xffffffUL )
 
#define portMAX_8_BIT_VALUE   ( ( uint8_t ) 0xff )
 
#define portMAX_PRIGROUP_BITS   ( ( uint8_t ) 7 )
 
#define portMISSED_COUNTS_FACTOR   ( 45UL )
 
#define portNVIC_IP_REGISTERS_OFFSET_16   ( 0xE000E3F0 )
 
#define portNVIC_PEND_SYSTICK_CLEAR_BIT   ( 1UL << 25UL )
 
#define portNVIC_PENDSV_PRI   ( ( ( uint32_t ) configKERNEL_INTERRUPT_PRIORITY ) << 16UL )
 
#define portNVIC_PENDSVCLEAR_BIT   ( 1UL << 27UL )
 
#define portNVIC_SYSPRI2_REG   ( * ( ( volatile uint32_t * ) 0xe000ed20 ) )
 
#define portNVIC_SYSTICK_CLK_BIT   ( 1UL << 2UL )
 
#define portNVIC_SYSTICK_COUNT_FLAG_BIT   ( 1UL << 16UL )
 
#define portNVIC_SYSTICK_CTRL_REG   ( * ( ( volatile uint32_t * ) 0xe000e010 ) )
 
#define portNVIC_SYSTICK_CURRENT_VALUE_REG   ( * ( ( volatile uint32_t * ) 0xe000e018 ) )
 
#define portNVIC_SYSTICK_ENABLE_BIT   ( 1UL << 0UL )
 
#define portNVIC_SYSTICK_INT_BIT   ( 1UL << 1UL )
 
#define portNVIC_SYSTICK_LOAD_REG   ( * ( ( volatile uint32_t * ) 0xe000e014 ) )
 
#define portNVIC_SYSTICK_PRI   ( ( ( uint32_t ) configKERNEL_INTERRUPT_PRIORITY ) << 24UL )
 
#define portPRIGROUP_SHIFT   ( 8UL )
 
#define portPRIORITY_GROUP_MASK   ( 0x07UL << 8UL )
 
#define portSTART_ADDRESS_MASK   ( ( StackType_t ) 0xfffffffeUL )
 
#define portTASK_RETURN_ADDRESS   prvTaskExitError
 
#define portTOP_BIT_OF_BYTE   ( ( uint8_t ) 0x80 )
 
#define portVECTACTIVE_MASK   ( 0xFFUL )
 

Functions

 __attribute__ ((weak))
 
static void prvPortStartFirstTask (void)
 
static void prvTaskExitError (void)
 
static void vPortEnableVFP (void)
 
void vPortEndScheduler (void)
 
void vPortEnterCritical (void)
 
void vPortExitCritical (void)
 
void vPortSetupTimerInterrupt (void)
 
void vPortSVCHandler (void)
 
void xPortPendSVHandler (void xPortSysTickHandler void)
 
void xPortPendSVHandler (void)
 
BaseType_t xPortStartScheduler (void)
 
void xPortSysTickHandler (void)
 

Macro Definition Documentation

◆ configSYSTICK_CLOCK_HZ

#define configSYSTICK_CLOCK_HZ   configCPU_CLOCK_HZ

Definition at line 42 of file port.c.

◆ portAIRCR_REG

#define portAIRCR_REG   ( * ( ( volatile uint32_t * ) 0xE000ED0C ) )

Definition at line 69 of file port.c.

◆ portASPEN_AND_LSPEN_BITS

#define portASPEN_AND_LSPEN_BITS   ( 0x3UL << 30UL )

Definition at line 81 of file port.c.

◆ portFIRST_USER_INTERRUPT_NUMBER

#define portFIRST_USER_INTERRUPT_NUMBER   ( 16 )

Definition at line 67 of file port.c.

◆ portFPCCR

#define portFPCCR   ( ( volatile uint32_t * ) 0xe000ef34 ) /* Floating point context control register. */

Definition at line 80 of file port.c.

◆ portINITIAL_EXC_RETURN

#define portINITIAL_EXC_RETURN   ( 0xfffffffd )

Definition at line 85 of file port.c.

◆ portINITIAL_XPSR

#define portINITIAL_XPSR   ( 0x01000000 )

Definition at line 84 of file port.c.

◆ portMAX_24_BIT_NUMBER

#define portMAX_24_BIT_NUMBER   ( 0xffffffUL )

Definition at line 88 of file port.c.

◆ portMAX_8_BIT_VALUE

#define portMAX_8_BIT_VALUE   ( ( uint8_t ) 0xff )

Definition at line 70 of file port.c.

◆ portMAX_PRIGROUP_BITS

#define portMAX_PRIGROUP_BITS   ( ( uint8_t ) 7 )

Definition at line 72 of file port.c.

◆ portMISSED_COUNTS_FACTOR

#define portMISSED_COUNTS_FACTOR   ( 45UL )

Definition at line 97 of file port.c.

◆ portNVIC_IP_REGISTERS_OFFSET_16

#define portNVIC_IP_REGISTERS_OFFSET_16   ( 0xE000E3F0 )

Definition at line 68 of file port.c.

◆ portNVIC_PEND_SYSTICK_CLEAR_BIT

#define portNVIC_PEND_SYSTICK_CLEAR_BIT   ( 1UL << 25UL )

Definition at line 61 of file port.c.

◆ portNVIC_PENDSV_PRI

#define portNVIC_PENDSV_PRI   ( ( ( uint32_t ) configKERNEL_INTERRUPT_PRIORITY ) << 16UL )

Definition at line 63 of file port.c.

◆ portNVIC_PENDSVCLEAR_BIT

#define portNVIC_PENDSVCLEAR_BIT   ( 1UL << 27UL )

Definition at line 60 of file port.c.

◆ portNVIC_SYSPRI2_REG

#define portNVIC_SYSPRI2_REG   ( * ( ( volatile uint32_t * ) 0xe000ed20 ) )

Definition at line 55 of file port.c.

◆ portNVIC_SYSTICK_CLK_BIT

#define portNVIC_SYSTICK_CLK_BIT   ( 1UL << 2UL )

Definition at line 44 of file port.c.

◆ portNVIC_SYSTICK_COUNT_FLAG_BIT

#define portNVIC_SYSTICK_COUNT_FLAG_BIT   ( 1UL << 16UL )

Definition at line 59 of file port.c.

◆ portNVIC_SYSTICK_CTRL_REG

#define portNVIC_SYSTICK_CTRL_REG   ( * ( ( volatile uint32_t * ) 0xe000e010 ) )

Definition at line 52 of file port.c.

◆ portNVIC_SYSTICK_CURRENT_VALUE_REG

#define portNVIC_SYSTICK_CURRENT_VALUE_REG   ( * ( ( volatile uint32_t * ) 0xe000e018 ) )

Definition at line 54 of file port.c.

◆ portNVIC_SYSTICK_ENABLE_BIT

#define portNVIC_SYSTICK_ENABLE_BIT   ( 1UL << 0UL )

Definition at line 58 of file port.c.

◆ portNVIC_SYSTICK_INT_BIT

#define portNVIC_SYSTICK_INT_BIT   ( 1UL << 1UL )

Definition at line 57 of file port.c.

◆ portNVIC_SYSTICK_LOAD_REG

#define portNVIC_SYSTICK_LOAD_REG   ( * ( ( volatile uint32_t * ) 0xe000e014 ) )

Definition at line 53 of file port.c.

◆ portNVIC_SYSTICK_PRI

#define portNVIC_SYSTICK_PRI   ( ( ( uint32_t ) configKERNEL_INTERRUPT_PRIORITY ) << 24UL )

Definition at line 64 of file port.c.

◆ portPRIGROUP_SHIFT

#define portPRIGROUP_SHIFT   ( 8UL )

Definition at line 74 of file port.c.

◆ portPRIORITY_GROUP_MASK

#define portPRIORITY_GROUP_MASK   ( 0x07UL << 8UL )

Definition at line 73 of file port.c.

◆ portSTART_ADDRESS_MASK

#define portSTART_ADDRESS_MASK   ( ( StackType_t ) 0xfffffffeUL )

Definition at line 92 of file port.c.

◆ portTASK_RETURN_ADDRESS

#define portTASK_RETURN_ADDRESS   prvTaskExitError

Definition at line 105 of file port.c.

◆ portTOP_BIT_OF_BYTE

#define portTOP_BIT_OF_BYTE   ( ( uint8_t ) 0x80 )

Definition at line 71 of file port.c.

◆ portVECTACTIVE_MASK

#define portVECTACTIVE_MASK   ( 0xFFUL )

Definition at line 77 of file port.c.

Function Documentation

◆ __attribute__()

__attribute__ ( (weak)  )

Definition at line 670 of file port.c.

◆ prvPortStartFirstTask()

static void prvPortStartFirstTask ( void  )
static

Definition at line 256 of file port.c.

◆ prvTaskExitError()

static void prvTaskExitError ( void  )
static

Definition at line 212 of file port.c.

◆ vPortEnableVFP()

static void vPortEnableVFP ( void  )
static

Definition at line 692 of file port.c.

◆ vPortEndScheduler()

void vPortEndScheduler ( void  )

Definition at line 384 of file port.c.

◆ vPortEnterCritical()

void vPortEnterCritical ( void  )

Definition at line 392 of file port.c.

◆ vPortExitCritical()

void vPortExitCritical ( void  )

Definition at line 409 of file port.c.

◆ vPortSetupTimerInterrupt()

void vPortSetupTimerInterrupt ( void  )

◆ vPortSVCHandler()

void vPortSVCHandler ( void  )

Definition at line 237 of file port.c.

◆ xPortPendSVHandler() [1/2]

void xPortPendSVHandler ( void xPortSysTickHandler  void)

Definition at line 118 of file port.c.

◆ xPortPendSVHandler() [2/2]

void xPortPendSVHandler ( void  )

Definition at line 420 of file port.c.

◆ xPortStartScheduler()

BaseType_t xPortStartScheduler ( void  )

Definition at line 282 of file port.c.

◆ xPortSysTickHandler()

void xPortSysTickHandler ( void  )

Definition at line 479 of file port.c.



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