System
- 1
+ 0
0
0
0
@@ -529,7 +529,7 @@
5
24
1
- 0
+ 1
0
0
..\main_full\IntQueueTimer.c
diff --git a/FreeRTOS/Demo/CORTEX_M4F_CEC1302_Keil_GCC/main.c b/FreeRTOS/Demo/CORTEX_M4F_CEC1302_Keil_GCC/main.c
index 37ada59901..4c843fa189 100644
--- a/FreeRTOS/Demo/CORTEX_M4F_CEC1302_Keil_GCC/main.c
+++ b/FreeRTOS/Demo/CORTEX_M4F_CEC1302_Keil_GCC/main.c
@@ -90,8 +90,9 @@
#include "task.h"
/* Hardware register addresses. */
-#define mainVTOR ( * ( uint32_t * ) 0xE000ED08 )
-#define mainNVIC_AUX_ACTLR ( * ( uint32_t * ) 0xE000E008 )
+#define mainVTOR ( * ( uint32_t * ) 0xE000ED08 )
+#define mainNVIC_AUX_ACTLR ( * ( uint32_t * ) 0xE000E008 )
+#define mainEC_INTERRUPT_CONTROL ( * ( volatile uint32_t * ) 0x4000FC18 )
/*-----------------------------------------------------------*/
@@ -163,12 +164,15 @@ static void prvSetupHardware( void )
{
extern void system_set_ec_clock( void );
extern unsigned long __Vectors[];
-
+
/* Disable M4 write buffer: fix MEC1322 hardware bug. */
mainNVIC_AUX_ACTLR |= 0x07;
+ /* Enable alternative NVIC vectors. */
+ mainEC_INTERRUPT_CONTROL = pdTRUE;
+
system_set_ec_clock();
-
+
/* Assuming downloading code via the debugger - so ensure the hardware
is using the vector table downloaded with the application. */
mainVTOR = ( uint32_t ) __Vectors;
diff --git a/FreeRTOS/Demo/CORTEX_M4F_CEC1302_Keil_GCC/main_full/IntQueueTimer.c b/FreeRTOS/Demo/CORTEX_M4F_CEC1302_Keil_GCC/main_full/IntQueueTimer.c
index bdc8e3d69f..6ff34e743a 100644
--- a/FreeRTOS/Demo/CORTEX_M4F_CEC1302_Keil_GCC/main_full/IntQueueTimer.c
+++ b/FreeRTOS/Demo/CORTEX_M4F_CEC1302_Keil_GCC/main_full/IntQueueTimer.c
@@ -119,7 +119,6 @@ timers must still be above the tick interrupt priority. */
/* Hardware register locations. */
#define tmrGIRQ23_ENABLE_SET ( * ( volatile uint32_t * ) 0x4000C130 )
-#define tmrMMCR_EC_INTERRUPT_CONTROL ( * ( volatile uint8_t * ) 0x4000FC18 )
#define tmrRECORD_NESTING_DEPTH() \
ulNestingDepth++; \
@@ -140,12 +139,11 @@ const uint32_t ulTimer1Count = configCPU_CLOCK_HZ / tmrTIMER_1_FREQUENCY;
const uint32_t ulTimer2Count = configCPU_CLOCK_HZ / tmrTIMER_2_FREQUENCY;
tmrGIRQ23_ENABLE_SET = 0x03;
- tmrMMCR_EC_INTERRUPT_CONTROL = 1;
-
- /* Initialise the three timers as described at the top of this file, and
+
+ /* Initialise the three timers as described at the top of this file, and
enable their interrupts in the NVIC. */
btimer_init( tmrTIMER_CHANNEL_0, BTIMER_AUTO_RESTART | BTIMER_COUNT_DOWN | BTIMER_INT_EN, 0, ulTimer0Count, ulTimer0Count );
- btimer_interrupt_status_get_clr( tmrTIMER_CHANNEL_0 );
+ btimer_interrupt_status_get_clr( tmrTIMER_CHANNEL_0 );
enable_timer0_irq();
NVIC_SetPriority( TIMER0_IRQn, tmrLOWER_PRIORITY ); //0xc0 into 0xe000e431
NVIC_ClearPendingIRQ( TIMER0_IRQn );
diff --git a/FreeRTOS/Demo/CORTEX_M4F_CEC1302_Keil_GCC/main_full/main_full.c b/FreeRTOS/Demo/CORTEX_M4F_CEC1302_Keil_GCC/main_full/main_full.c
index a2deb7adc9..834acd4c5b 100644
--- a/FreeRTOS/Demo/CORTEX_M4F_CEC1302_Keil_GCC/main_full/main_full.c
+++ b/FreeRTOS/Demo/CORTEX_M4F_CEC1302_Keil_GCC/main_full/main_full.c
@@ -355,8 +355,7 @@ unsigned long ulErrorFound = pdFALSE;
{
/* An error has been detected in one of the tasks - flash the LED
at a higher frequency to give visible feedback that something has
- gone wrong (it might just be that the loop back connector required
- by the comtest tasks has not been fitted). */
+ gone wrong. */
xDelayPeriod = mainERROR_CHECK_TASK_PERIOD;
}
diff --git a/FreeRTOS/Demo/CORTEX_M4F_CEC1302_Keil_GCC/main_low_power/low_power_tick_config.c b/FreeRTOS/Demo/CORTEX_M4F_CEC1302_Keil_GCC/main_low_power/low_power_tick_config.c
index dbc969d727..1d509e7cf5 100644
--- a/FreeRTOS/Demo/CORTEX_M4F_CEC1302_Keil_GCC/main_low_power/low_power_tick_config.c
+++ b/FreeRTOS/Demo/CORTEX_M4F_CEC1302_Keil_GCC/main_low_power/low_power_tick_config.c
@@ -134,12 +134,10 @@ static const uint32_t ulHighResolutionReloadValue = ( mainHIGHER_RESOLUTION_TIME
/* Calculate how many clock increments make up a single tick period. */
static const uint32_t ulReloadValueForOneHighResolutionTick = ( mainHIGHER_RESOLUTION_TIMER_HZ / configTICK_RATE_HZ );
-//static const uint32_t usReloadValueForOneLowResolutionTick = ( mainLOW_RESOLUTION_TIMER_HZ / configTICK_RATE_HZ );
/* Calculate the maximum number of ticks that can be suppressed when using the
high resolution clock and low resolution clock respectively. */
static uint32_t ulMaximumPossibleSuppressedHighResolutionTicks = 0;
-//static const uint16_t usMaximumPossibleSuppressedLowResolutionTicks = USHRT_MAX / usReloadValueForOneLowResolutionTick;
/* As the clock is only 2KHz, it is likely a value of 1 will be too much, so
use zero - but leave the value here to assist porting to different clock
@@ -171,15 +169,14 @@ void NVIC_Handler_HIB_TMR( void )
#if( lpINCLUDE_TEST_TIMER == 1 )
- #define GIRQ23_ENABLE_SET ( * ( uint32_t * ) 0x4000C130 )
+ #define lpGIRQ23_ENABLE_SET ( * ( uint32_t * ) 0x4000C130 )
static void prvSetupBasicTimer( void )
{
const uint8_t ucTimerChannel = 0;
const uint32_t ulTimer0Count = configCPU_CLOCK_HZ / 10;
- GIRQ23_ENABLE_SET = 0x03;
- *(unsigned int*)0x4000FC18 = 1;
+ lpGIRQ23_ENABLE_SET = 0x03;
/* To fully test the low power tick processing it is necessary to sometimes
bring the MCU out of its sleep state by a method other than the tick
@@ -202,9 +199,7 @@ void vPortSetupTimerInterrupt( void )
ulMaximumPossibleSuppressedHighResolutionTicks = ( ( uint32_t ) USHRT_MAX ) / ulReloadValueForOneHighResolutionTick;
/* Set up the hibernation timer to start at the value required by the
- tick interrupt. Equivalent to the following libarary call. The library
- is not used as it is not compatible with all the compilers used:
- htimer_enable( mainTICK_HTIMER_ID, ulHighResolutionReloadValue, mainHTIMER_HIGH_RESOLUTION ); */
+ tick interrupt. */
lpHTIMER_PRELOAD_REGISTER = ulHighResolutionReloadValue;
lpHTIMER_CONTROL_REGISTER = mainHTIMER_HIGH_RESOLUTION;
@@ -285,7 +280,7 @@ TickType_t xModifiableIdleTime;
eSleepAction = eTaskConfirmSleepModeStatus();
if( eSleepAction == eAbortSleep )
{
- /* Resetart the timer from whatever remains in the counter register,
+ /* Restart the timer from whatever remains in the counter register,
but 0 is not a valid value. */
ulReloadValue = ulCountBeforeSleep - ulStoppedTimerCompensation;
diff --git a/FreeRTOS/Demo/Common/Minimal/AbortDelay.c b/FreeRTOS/Demo/Common/Minimal/AbortDelay.c
index 2a9fd82e24..349c1cb58d 100644
--- a/FreeRTOS/Demo/Common/Minimal/AbortDelay.c
+++ b/FreeRTOS/Demo/Common/Minimal/AbortDelay.c
@@ -89,8 +89,8 @@
build. Remove the whole file if this is not the case. */
#if( INCLUDE_xTaskAbortDelay == 1 )
-#if( INCLUDE_xTaskGetTaskHandle != 1 )
- #error This test file uses the xTaskGetTaskHandle() API function so INCLUDE_xTaskGetTaskHandle must be set to 1 in FreeRTOSConfig.h.
+#if( INCLUDE_xTaskGetHandle != 1 )
+ #error This test file uses the xTaskGetHandle() API function so INCLUDE_xTaskGetHandle must be set to 1 in FreeRTOSConfig.h.
#endif
/* Task priorities. Allow these to be overridden. */
@@ -183,7 +183,7 @@ const TickType_t xStartMargin = 2UL;
/* Just to remove compiler warnings. */
( void ) pvParameters;
- xBlockingTask = xTaskGetTaskHandle( pcBlockingTaskName );
+ xBlockingTask = xTaskGetHandle( pcBlockingTaskName );
configASSERT( xBlockingTask );
for( ;; )
@@ -241,7 +241,7 @@ uint32_t ulNotificationValue;
/* Just to remove compiler warnings. */
( void ) pvParameters;
- xControllingTask = xTaskGetTaskHandle( pcControllingTaskName );
+ xControllingTask = xTaskGetHandle( pcControllingTaskName );
configASSERT( xControllingTask );
for( ;; )
diff --git a/FreeRTOS/Demo/WIN32-MSVC-Static-Allocation-Only/FreeRTOSConfig.h b/FreeRTOS/Demo/WIN32-MSVC-Static-Allocation-Only/FreeRTOSConfig.h
index b10ce79de3..cf163313a4 100644
--- a/FreeRTOS/Demo/WIN32-MSVC-Static-Allocation-Only/FreeRTOSConfig.h
+++ b/FreeRTOS/Demo/WIN32-MSVC-Static-Allocation-Only/FreeRTOSConfig.h
@@ -154,7 +154,7 @@ functions anyway. */
#define INCLUDE_xTaskGetSchedulerState 1
#define INCLUDE_xTimerGetTimerDaemonTaskHandle 1
#define INCLUDE_xTaskGetIdleTaskHandle 1
-#define INCLUDE_xTaskGetTaskHandle 1
+#define INCLUDE_xTaskGetHandle 1
#define INCLUDE_eTaskGetState 1
#define INCLUDE_xSemaphoreGetMutexHolder 1
#define INCLUDE_xTimerPendFunctionCall 1
diff --git a/FreeRTOS/Demo/WIN32-MSVC/FreeRTOSConfig.h b/FreeRTOS/Demo/WIN32-MSVC/FreeRTOSConfig.h
index 0523a675f5..38ef2ec5c2 100644
--- a/FreeRTOS/Demo/WIN32-MSVC/FreeRTOSConfig.h
+++ b/FreeRTOS/Demo/WIN32-MSVC/FreeRTOSConfig.h
@@ -145,7 +145,7 @@ functions anyway. */
#define INCLUDE_xTaskGetSchedulerState 1
#define INCLUDE_xTimerGetTimerDaemonTaskHandle 1
#define INCLUDE_xTaskGetIdleTaskHandle 1
-#define INCLUDE_xTaskGetTaskHandle 1
+#define INCLUDE_xTaskGetHandle 1
#define INCLUDE_eTaskGetState 1
#define INCLUDE_xSemaphoreGetMutexHolder 1
#define INCLUDE_xTimerPendFunctionCall 1
diff --git a/FreeRTOS/Demo/WIN32-MSVC/main_full.c b/FreeRTOS/Demo/WIN32-MSVC/main_full.c
index efa214730f..8af29dbaaa 100644
--- a/FreeRTOS/Demo/WIN32-MSVC/main_full.c
+++ b/FreeRTOS/Demo/WIN32-MSVC/main_full.c
@@ -599,12 +599,12 @@ extern StackType_t uxTimerTaskStack[];
/* Check the same handle is obtained using the idle task's name. First try
with the wrong name, then the right name. */
- if( xTaskGetTaskHandle( "Idle" ) == xIdleTaskHandle )
+ if( xTaskGetHandle( "Idle" ) == xIdleTaskHandle )
{
pcStatusMessage = "Error: Returned handle for name Idle was incorrect";
}
- if( xTaskGetTaskHandle( "IDLE" ) != xIdleTaskHandle )
+ if( xTaskGetHandle( "IDLE" ) != xIdleTaskHandle )
{
pcStatusMessage = "Error: Returned handle for name Idle was incorrect";
}
@@ -616,7 +616,7 @@ extern StackType_t uxTimerTaskStack[];
pcStatusMessage = "Error: Returned timer task handle was incorrect";
}
- if( xTaskGetTaskHandle( "Tmr Svc" ) != xTimerTaskHandle )
+ if( xTaskGetHandle( "Tmr Svc" ) != xTimerTaskHandle )
{
pcStatusMessage = "Error: Returned handle for name Tmr Svc was incorrect";
}
@@ -633,20 +633,20 @@ extern StackType_t uxTimerTaskStack[];
pcStatusMessage = "Error: Returned timer task state was incorrect";
}
- /* Also with the vTaskGetTaskInfo() function. */
- vTaskGetTaskInfo( xTimerTaskHandle, /* The task being queried. */
+ /* Also with the vTaskGetInfo() function. */
+ vTaskGetInfo( xTimerTaskHandle, /* The task being queried. */
&xTaskInfo, /* The structure into which information on the task will be written. */
pdTRUE, /* Include the task's high watermark in the structure. */
eInvalid ); /* Include the task state in the structure. */
- /* Check the information returned by vTaskGetTaskInfo() is as expected. */
+ /* Check the information returned by vTaskGetInfo() is as expected. */
if( ( xTaskInfo.eCurrentState != eBlocked ) ||
( strcmp( xTaskInfo.pcTaskName, "Tmr Svc" ) != 0 ) ||
( xTaskInfo.uxCurrentPriority != configTIMER_TASK_PRIORITY ) ||
( xTaskInfo.pxStackBase != uxTimerTaskStack ) ||
( xTaskInfo.xHandle != xTimerTaskHandle ) )
{
- pcStatusMessage = "Error: vTaskGetTaskInfo() returned incorrect information about the timer task";
+ pcStatusMessage = "Error: vTaskGetInfo() returned incorrect information about the timer task";
}
/* Other tests that should only be performed once follow. The test task
diff --git a/FreeRTOS/Demo/WIN32-MingW/FreeRTOSConfig.h b/FreeRTOS/Demo/WIN32-MingW/FreeRTOSConfig.h
index b72bbb557d..07d57b6aad 100644
--- a/FreeRTOS/Demo/WIN32-MingW/FreeRTOSConfig.h
+++ b/FreeRTOS/Demo/WIN32-MingW/FreeRTOSConfig.h
@@ -147,7 +147,7 @@ functions anyway. */
#define INCLUDE_xSemaphoreGetMutexHolder 1
#define INCLUDE_xTimerPendFunctionCall 1
#define INCLUDE_xTaskAbortDelay 1
-#define INCLUDE_xTaskGetTaskHandle 1
+#define INCLUDE_xTaskGetHandle 1
/* It is a good idea to define configASSERT() while developing. configASSERT()
uses the same semantics as the standard C assert() macro. */
diff --git a/FreeRTOS/Source/include/FreeRTOS.h b/FreeRTOS/Source/include/FreeRTOS.h
index 1051293e85..a902a34ac3 100644
--- a/FreeRTOS/Source/include/FreeRTOS.h
+++ b/FreeRTOS/Source/include/FreeRTOS.h
@@ -181,8 +181,8 @@ extern "C" {
#define INCLUDE_xSemaphoreGetMutexHolder INCLUDE_xQueueGetMutexHolder
#endif
-#ifndef INCLUDE_xTaskGetTaskHandle
- #define INCLUDE_xTaskGetTaskHandle 0
+#ifndef INCLUDE_xTaskGetHandle
+ #define INCLUDE_xTaskGetHandle 0
#endif
#ifndef INCLUDE_uxTaskGetStackHighWaterMark
@@ -837,6 +837,8 @@ V8 if desired. */
#define portTICK_RATE_MS portTICK_PERIOD_MS
#define pcTaskGetTaskName pcTaskGetName
#define pcTimerGetTimerName pcTimerGetName
+ #define pcQueueGetQueueName pcQueueGetName
+ #define vTaskGetTaskInfo vTaskGetInfo
/* Backward compatibility within the scheduler code only - these definitions
are not really required but are included for completeness. */
diff --git a/FreeRTOS/Source/include/semphr.h b/FreeRTOS/Source/include/semphr.h
index 46c3e1accf..9a61599d82 100644
--- a/FreeRTOS/Source/include/semphr.h
+++ b/FreeRTOS/Source/include/semphr.h
@@ -421,7 +421,9 @@ typedef QueueHandle_t SemaphoreHandle_t;
* \defgroup xSemaphoreTakeRecursive xSemaphoreTakeRecursive
* \ingroup Semaphores
*/
-#define xSemaphoreTakeRecursive( xMutex, xBlockTime ) xQueueTakeMutexRecursive( ( xMutex ), ( xBlockTime ) )
+#if( configUSE_RECURSIVE_MUTEXES == 1 )
+ #define xSemaphoreTakeRecursive( xMutex, xBlockTime ) xQueueTakeMutexRecursive( ( xMutex ), ( xBlockTime ) )
+#endif
/**
* semphr. h
@@ -568,7 +570,9 @@ typedef QueueHandle_t SemaphoreHandle_t;
* \defgroup xSemaphoreGiveRecursive xSemaphoreGiveRecursive
* \ingroup Semaphores
*/
-#define xSemaphoreGiveRecursive( xMutex ) xQueueGiveMutexRecursive( ( xMutex ) )
+#if( configUSE_RECURSIVE_MUTEXES == 1 )
+ #define xSemaphoreGiveRecursive( xMutex ) xQueueGiveMutexRecursive( ( xMutex ) )
+#endif
/**
* semphr. h
@@ -879,7 +883,7 @@ typedef QueueHandle_t SemaphoreHandle_t;
* \defgroup xSemaphoreCreateRecursiveMutex xSemaphoreCreateRecursiveMutex
* \ingroup Semaphores
*/
-#if( configSUPPORT_DYNAMIC_ALLOCATION == 1 )
+#if( ( configSUPPORT_DYNAMIC_ALLOCATION == 1 ) && ( configUSE_RECURSIVE_MUTEXES == 1 ) )
#define xSemaphoreCreateRecursiveMutex() xQueueCreateMutex( queueQUEUE_TYPE_RECURSIVE_MUTEX )
#endif
@@ -952,7 +956,7 @@ typedef QueueHandle_t SemaphoreHandle_t;
* \defgroup xSemaphoreCreateRecursiveMutexStatic xSemaphoreCreateRecursiveMutexStatic
* \ingroup Semaphores
*/
-#if( configSUPPORT_STATIC_ALLOCATION == 1 )
+#if( ( configSUPPORT_STATIC_ALLOCATION == 1 ) && ( configUSE_RECURSIVE_MUTEXES == 1 ) )
#define xSemaphoreCreateRecursiveMutexStatic( pxStaticSemaphore ) xQueueCreateMutexStatic( queueQUEUE_TYPE_RECURSIVE_MUTEX, pxStaticSemaphore )
#endif /* configSUPPORT_STATIC_ALLOCATION */
@@ -1152,7 +1156,7 @@ typedef QueueHandle_t SemaphoreHandle_t;
/**
* semphr.h
- * UBaseType_t uxSemaphoreGetCount( SemaphoreHandle_t xMutex );
+ * UBaseType_t uxSemaphoreGetCount( SemaphoreHandle_t xSemaphore );
*
* If the semaphore is a counting semaphore then uxSemaphoreGetCount() returns
* its current count value. If the semaphore is a binary semaphore then
diff --git a/FreeRTOS/Source/include/task.h b/FreeRTOS/Source/include/task.h
index 385c66388d..c4bc0838da 100644
--- a/FreeRTOS/Source/include/task.h
+++ b/FreeRTOS/Source/include/task.h
@@ -840,7 +840,7 @@ eTaskState eTaskGetState( TaskHandle_t xTask ) PRIVILEGED_FUNCTION;
/**
* task. h
- * void vTaskGetTaskInfo( TaskHandle_t xTask, TaskStatus_t *pxTaskStatus, BaseType_t xGetFreeStackSpace, eTaskState eState );
+ * void vTaskGetInfo( TaskHandle_t xTask, TaskStatus_t *pxTaskStatus, BaseType_t xGetFreeStackSpace, eTaskState eState );
*
* configUSE_TRACE_FACILITY must be defined as 1 for this function to be
* available. See the configuration section for more information.
@@ -877,22 +877,22 @@ eTaskState eTaskGetState( TaskHandle_t xTask ) PRIVILEGED_FUNCTION;
TaskStatus_t xTaskDetails;
// Obtain the handle of a task from its name.
- xHandle = xTaskGetTaskHandle( "Task_Name" );
+ xHandle = xTaskGetHandle( "Task_Name" );
// Check the handle is not NULL.
configASSERT( xHandle );
// Use the handle to obtain further information about the task.
- vTaskGetTaskInfo( xHandle,
- &xTaskDetails,
- pdTRUE, // Include the high water mark in xTaskDetails.
- eInvalid ); // Include the task state in xTaskDetails.
+ vTaskGetInfo( xHandle,
+ &xTaskDetails,
+ pdTRUE, // Include the high water mark in xTaskDetails.
+ eInvalid ); // Include the task state in xTaskDetails.
}
- * \defgroup vTaskGetTaskInfo vTaskGetTaskInfo
+ * \defgroup vTaskGetInfo vTaskGetInfo
* \ingroup TaskCtrl
*/
-void vTaskGetTaskInfo( TaskHandle_t xTask, TaskStatus_t *pxTaskStatus, BaseType_t xGetFreeStackSpace, eTaskState eState ) PRIVILEGED_FUNCTION;
+void vTaskGetInfo( TaskHandle_t xTask, TaskStatus_t *pxTaskStatus, BaseType_t xGetFreeStackSpace, eTaskState eState ) PRIVILEGED_FUNCTION;
/**
* task. h
@@ -1319,19 +1319,19 @@ char *pcTaskGetName( TaskHandle_t xTaskToQuery ) PRIVILEGED_FUNCTION; /*lint !e9
/**
* task. h
- * TaskHandle_t xTaskGetTaskHandle( const char *pcNameToQuery );
+ * TaskHandle_t xTaskGetHandle( const char *pcNameToQuery );
*
* NOTE: This function takes a relatively long time to complete and should be
* used sparingly.
*
* @return The handle of the task that has the human readable name pcNameToQuery.
- * NULL is returned if no matching name is found. INCLUDE_xTaskGetTaskHandle
- * must be set to 1 in FreeRTOSConfig.h for pcTaskGetTaskHandle() to be available.
+ * NULL is returned if no matching name is found. INCLUDE_xTaskGetHandle
+ * must be set to 1 in FreeRTOSConfig.h for pcTaskGetHandle() to be available.
*
- * \defgroup pcTaskGetTaskHandle pcTaskGetTaskHandle
+ * \defgroup pcTaskGetHandle pcTaskGetHandle
* \ingroup TaskUtils
*/
-TaskHandle_t xTaskGetTaskHandle( const char *pcNameToQuery ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+TaskHandle_t xTaskGetHandle( const char *pcNameToQuery ) PRIVILEGED_FUNCTION; /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
/**
* task.h
diff --git a/FreeRTOS/Source/portable/CCS/ARM_CM4F/port.c b/FreeRTOS/Source/portable/CCS/ARM_CM4F/port.c
index bf423b8c88..a02254419f 100644
--- a/FreeRTOS/Source/portable/CCS/ARM_CM4F/port.c
+++ b/FreeRTOS/Source/portable/CCS/ARM_CM4F/port.c
@@ -137,6 +137,10 @@ occurred while the SysTick counter is stopped during tickless idle
calculations. */
#define portMISSED_COUNTS_FACTOR ( 45UL )
+/* For strict compliance with the Cortex-M spec the task start address should
+have bit-0 clear, as it is loaded into the PC on exit from an ISR. */
+#define portSTART_ADDRESS_MASK ( ( StackType_t ) 0xfffffffeUL )
+
/* Required to allow portasm.asm access the configMAX_SYSCALL_INTERRUPT_PRIORITY
setting. */
const uint32_t ulMaxSyscallInterruptPriority = configMAX_SYSCALL_INTERRUPT_PRIORITY;
@@ -224,7 +228,7 @@ StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t px
*pxTopOfStack = portINITIAL_XPSR; /* xPSR */
pxTopOfStack--;
- *pxTopOfStack = ( StackType_t ) pxCode; /* PC */
+ *pxTopOfStack = ( ( StackType_t ) pxCode ) & portSTART_ADDRESS_MASK; /* PC */
pxTopOfStack--;
*pxTopOfStack = ( StackType_t ) prvTaskExitError; /* LR */
@@ -419,6 +423,9 @@ void xPortSysTickHandler( void )
/* Enter a critical section but don't use the taskENTER_CRITICAL()
method as that will mask interrupts that should exit sleep mode. */
__asm( " cpsid i" );
+ __asm( " dsb" );
+ __asm( " isb" );
+
/* If a context switch is pending or a task is waiting for the scheduler
to be unsuspended then abandon the low power entry. */
diff --git a/FreeRTOS/Source/portable/GCC/ARM_CM3/port.c b/FreeRTOS/Source/portable/GCC/ARM_CM3/port.c
index 74549259f0..e72fc3ec48 100644
--- a/FreeRTOS/Source/portable/GCC/ARM_CM3/port.c
+++ b/FreeRTOS/Source/portable/GCC/ARM_CM3/port.c
@@ -131,6 +131,10 @@ occurred while the SysTick counter is stopped during tickless idle
calculations. */
#define portMISSED_COUNTS_FACTOR ( 45UL )
+/* For strict compliance with the Cortex-M spec the task start address should
+have bit-0 clear, as it is loaded into the PC on exit from an ISR. */
+#define portSTART_ADDRESS_MASK ( ( StackType_t ) 0xfffffffeUL )
+
/* Let the user override the pre-loading of the initial LR with the address of
prvTaskExitError() in case it messes up unwinding of the stack in the
debugger. */
@@ -216,7 +220,7 @@ StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t px
pxTopOfStack--; /* Offset added to account for the way the MCU uses the stack on entry/exit of interrupts. */
*pxTopOfStack = portINITIAL_XPSR; /* xPSR */
pxTopOfStack--;
- *pxTopOfStack = ( StackType_t ) pxCode; /* PC */
+ *pxTopOfStack = ( ( StackType_t ) pxCode ) & portSTART_ADDRESS_MASK; /* PC */
pxTopOfStack--;
*pxTopOfStack = ( StackType_t ) portTASK_RETURN_ADDRESS; /* LR */
pxTopOfStack -= 5; /* R12, R3, R2 and R1. */
@@ -480,6 +484,8 @@ void xPortSysTickHandler( void )
/* Enter a critical section but don't use the taskENTER_CRITICAL()
method as that will mask interrupts that should exit sleep mode. */
__asm volatile( "cpsid i" );
+ __asm volatile( "dsb" );
+ __asm volatile( "isb" );
/* If a context switch is pending or a task is waiting for the scheduler
to be unsuspended then abandon the low power entry. */
diff --git a/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c b/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c
index 2da512f941..855a3b746f 100644
--- a/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c
+++ b/FreeRTOS/Source/portable/GCC/ARM_CM4F/port.c
@@ -134,6 +134,10 @@ r0p1 port. */
/* The systick is a 24-bit counter. */
#define portMAX_24_BIT_NUMBER ( 0xffffffUL )
+/* For strict compliance with the Cortex-M spec the task start address should
+have bit-0 clear, as it is loaded into the PC on exit from an ISR. */
+#define portSTART_ADDRESS_MASK ( ( StackType_t ) 0xfffffffeUL )
+
/* A fiddle factor to estimate the number of SysTick counts that would have
occurred while the SysTick counter is stopped during tickless idle
calculations. */
@@ -233,7 +237,7 @@ StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t px
*pxTopOfStack = portINITIAL_XPSR; /* xPSR */
pxTopOfStack--;
- *pxTopOfStack = ( StackType_t ) pxCode; /* PC */
+ *pxTopOfStack = ( ( StackType_t ) pxCode ) & portSTART_ADDRESS_MASK; /* PC */
pxTopOfStack--;
*pxTopOfStack = ( StackType_t ) portTASK_RETURN_ADDRESS; /* LR */
@@ -537,6 +541,8 @@ void xPortSysTickHandler( void )
/* Enter a critical section but don't use the taskENTER_CRITICAL()
method as that will mask interrupts that should exit sleep mode. */
__asm volatile( "cpsid i" );
+ __asm volatile( "dsb" );
+ __asm volatile( "isb" );
/* If a context switch is pending or a task is waiting for the scheduler
to be unsuspended then abandon the low power entry. */
diff --git a/FreeRTOS/Source/portable/GCC/ARM_CM7/r0p1/port.c b/FreeRTOS/Source/portable/GCC/ARM_CM7/r0p1/port.c
index fc8fbabb1b..d585aa7ad4 100644
--- a/FreeRTOS/Source/portable/GCC/ARM_CM7/r0p1/port.c
+++ b/FreeRTOS/Source/portable/GCC/ARM_CM7/r0p1/port.c
@@ -133,6 +133,10 @@ occurred while the SysTick counter is stopped during tickless idle
calculations. */
#define portMISSED_COUNTS_FACTOR ( 45UL )
+/* For strict compliance with the Cortex-M spec the task start address should
+have bit-0 clear, as it is loaded into the PC on exit from an ISR. */
+#define portSTART_ADDRESS_MASK ( ( StackType_t ) 0xfffffffeUL )
+
/* Let the user override the pre-loading of the initial LR with the address of
prvTaskExitError() in case it messes up unwinding of the stack in the
debugger. */
@@ -227,7 +231,7 @@ StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t px
*pxTopOfStack = portINITIAL_XPSR; /* xPSR */
pxTopOfStack--;
- *pxTopOfStack = ( StackType_t ) pxCode; /* PC */
+ *pxTopOfStack = ( ( StackType_t ) pxCode ) & portSTART_ADDRESS_MASK; /* PC */
pxTopOfStack--;
*pxTopOfStack = ( StackType_t ) portTASK_RETURN_ADDRESS; /* LR */
@@ -527,6 +531,8 @@ void xPortSysTickHandler( void )
/* Enter a critical section but don't use the taskENTER_CRITICAL()
method as that will mask interrupts that should exit sleep mode. */
__asm volatile( "cpsid i" );
+ __asm volatile( "dsb" );
+ __asm volatile( "isb" );
/* If a context switch is pending or a task is waiting for the scheduler
to be unsuspended then abandon the low power entry. */
diff --git a/FreeRTOS/Source/portable/GCC/ARM_CR5/port.c b/FreeRTOS/Source/portable/GCC/ARM_CR5/port.c
index 0f1a186985..b7eab92bdd 100644
--- a/FreeRTOS/Source/portable/GCC/ARM_CR5/port.c
+++ b/FreeRTOS/Source/portable/GCC/ARM_CR5/port.c
@@ -555,7 +555,7 @@ uint32_t ulReturn;
this is not the case (if some bits represent a sub-priority).
The priority grouping is configured by the GIC's binary point register
- (ICCBPR). Writting 0 to ICCBPR will ensure it is set to its lowest
+ (ICCBPR). Writing 0 to ICCBPR will ensure it is set to its lowest
possible value (which may be above 0). */
configASSERT( ( portICCBPR_BINARY_POINT_REGISTER & portBINARY_POINT_BITS ) <= portMAX_BINARY_POINT_VALUE );
}
diff --git a/FreeRTOS/Source/portable/IAR/ARM_CM3/port.c b/FreeRTOS/Source/portable/IAR/ARM_CM3/port.c
index 9be08e37a0..bcbe25cb19 100644
--- a/FreeRTOS/Source/portable/IAR/ARM_CM3/port.c
+++ b/FreeRTOS/Source/portable/IAR/ARM_CM3/port.c
@@ -131,6 +131,10 @@ occurred while the SysTick counter is stopped during tickless idle
calculations. */
#define portMISSED_COUNTS_FACTOR ( 45UL )
+/* For strict compliance with the Cortex-M spec the task start address should
+have bit-0 clear, as it is loaded into the PC on exit from an ISR. */
+#define portSTART_ADDRESS_MASK ( ( StackType_t ) 0xfffffffeUL )
+
/* For backward compatibility, ensure configKERNEL_INTERRUPT_PRIORITY is
defined. The value 255 should also ensure backward compatibility.
FreeRTOS.org versions prior to V4.3.0 did not include this definition. */
@@ -212,7 +216,7 @@ StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t px
pxTopOfStack--; /* Offset added to account for the way the MCU uses the stack on entry/exit of interrupts. */
*pxTopOfStack = portINITIAL_XPSR; /* xPSR */
pxTopOfStack--;
- *pxTopOfStack = ( StackType_t ) pxCode; /* PC */
+ *pxTopOfStack = ( ( StackType_t ) pxCode ) & portSTART_ADDRESS_MASK; /* PC */
pxTopOfStack--;
*pxTopOfStack = ( StackType_t ) prvTaskExitError; /* LR */
pxTopOfStack -= 5; /* R12, R3, R2 and R1. */
@@ -392,6 +396,9 @@ void xPortSysTickHandler( void )
/* Enter a critical section but don't use the taskENTER_CRITICAL()
method as that will mask interrupts that should exit sleep mode. */
__disable_interrupt();
+ __DSB();
+ __ISB();
+
/* If a context switch is pending or a task is waiting for the scheduler
to be unsuspended then abandon the low power entry. */
diff --git a/FreeRTOS/Source/portable/IAR/ARM_CM4F/port.c b/FreeRTOS/Source/portable/IAR/ARM_CM4F/port.c
index ec58192761..b66c4873ed 100644
--- a/FreeRTOS/Source/portable/IAR/ARM_CM4F/port.c
+++ b/FreeRTOS/Source/portable/IAR/ARM_CM4F/port.c
@@ -146,6 +146,9 @@ occurred while the SysTick counter is stopped during tickless idle
calculations. */
#define portMISSED_COUNTS_FACTOR ( 45UL )
+/* For strict compliance with the Cortex-M spec the task start address should
+have bit-0 clear, as it is loaded into the PC on exit from an ISR. */
+#define portSTART_ADDRESS_MASK ( ( StackType_t ) 0xfffffffeUL )
/* Each task maintains its own interrupt status in the critical nesting
variable. */
@@ -230,7 +233,7 @@ StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t px
*pxTopOfStack = portINITIAL_XPSR; /* xPSR */
pxTopOfStack--;
- *pxTopOfStack = ( StackType_t ) pxCode; /* PC */
+ *pxTopOfStack = ( ( StackType_t ) pxCode ) & portSTART_ADDRESS_MASK; /* PC */
pxTopOfStack--;
*pxTopOfStack = ( StackType_t ) prvTaskExitError; /* LR */
@@ -434,6 +437,9 @@ void xPortSysTickHandler( void )
/* Enter a critical section but don't use the taskENTER_CRITICAL()
method as that will mask interrupts that should exit sleep mode. */
__disable_interrupt();
+ __DSB();
+ __ISB();
+
/* If a context switch is pending or a task is waiting for the scheduler
to be unsuspended then abandon the low power entry. */
diff --git a/FreeRTOS/Source/portable/IAR/ARM_CM7/r0p1/port.c b/FreeRTOS/Source/portable/IAR/ARM_CM7/r0p1/port.c
index 3b1e1ed468..ce9c879350 100644
--- a/FreeRTOS/Source/portable/IAR/ARM_CM7/r0p1/port.c
+++ b/FreeRTOS/Source/portable/IAR/ARM_CM7/r0p1/port.c
@@ -140,6 +140,9 @@ occurred while the SysTick counter is stopped during tickless idle
calculations. */
#define portMISSED_COUNTS_FACTOR ( 45UL )
+/* For strict compliance with the Cortex-M spec the task start address should
+have bit-0 clear, as it is loaded into the PC on exit from an ISR. */
+#define portSTART_ADDRESS_MASK ( ( StackType_t ) 0xfffffffeUL )
/* Each task maintains its own interrupt status in the critical nesting
variable. */
@@ -224,7 +227,7 @@ StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t px
*pxTopOfStack = portINITIAL_XPSR; /* xPSR */
pxTopOfStack--;
- *pxTopOfStack = ( StackType_t ) pxCode; /* PC */
+ *pxTopOfStack = ( ( StackType_t ) pxCode ) & portSTART_ADDRESS_MASK; /* PC */
pxTopOfStack--;
*pxTopOfStack = ( StackType_t ) prvTaskExitError; /* LR */
@@ -418,6 +421,8 @@ void xPortSysTickHandler( void )
/* Enter a critical section but don't use the taskENTER_CRITICAL()
method as that will mask interrupts that should exit sleep mode. */
__disable_interrupt();
+ __DSB();
+ __ISB();
/* If a context switch is pending or a task is waiting for the scheduler
to be unsuspended then abandon the low power entry. */
diff --git a/FreeRTOS/Source/portable/RVDS/ARM_CM3/port.c b/FreeRTOS/Source/portable/RVDS/ARM_CM3/port.c
index f9528e50ae..45a8f565d8 100644
--- a/FreeRTOS/Source/portable/RVDS/ARM_CM3/port.c
+++ b/FreeRTOS/Source/portable/RVDS/ARM_CM3/port.c
@@ -141,6 +141,10 @@ occurred while the SysTick counter is stopped during tickless idle
calculations. */
#define portMISSED_COUNTS_FACTOR ( 45UL )
+/* For strict compliance with the Cortex-M spec the task start address should
+have bit-0 clear, as it is loaded into the PC on exit from an ISR. */
+#define portSTART_ADDRESS_MASK ( ( StackType_t ) 0xfffffffeUL )
+
/* Each task maintains its own interrupt status in the critical nesting
variable. */
static UBaseType_t uxCriticalNesting = 0xaaaaaaaa;
@@ -217,7 +221,7 @@ StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t px
pxTopOfStack--; /* Offset added to account for the way the MCU uses the stack on entry/exit of interrupts. */
*pxTopOfStack = portINITIAL_XPSR; /* xPSR */
pxTopOfStack--;
- *pxTopOfStack = ( StackType_t ) pxCode; /* PC */
+ *pxTopOfStack = ( ( StackType_t ) pxCode ) & portSTART_ADDRESS_MASK; /* PC */
pxTopOfStack--;
*pxTopOfStack = ( StackType_t ) prvTaskExitError; /* LR */
@@ -476,6 +480,8 @@ void xPortSysTickHandler( void )
/* Enter a critical section but don't use the taskENTER_CRITICAL()
method as that will mask interrupts that should exit sleep mode. */
__disable_irq();
+ __dsb( portSY_FULL_READ_WRITE );
+ __isb( portSY_FULL_READ_WRITE );
/* If a context switch is pending or a task is waiting for the scheduler
to be unsuspended then abandon the low power entry. */
diff --git a/FreeRTOS/Source/portable/RVDS/ARM_CM4F/port.c b/FreeRTOS/Source/portable/RVDS/ARM_CM4F/port.c
index 2be9b4fbca..bb128f8e43 100644
--- a/FreeRTOS/Source/portable/RVDS/ARM_CM4F/port.c
+++ b/FreeRTOS/Source/portable/RVDS/ARM_CM4F/port.c
@@ -145,12 +145,16 @@ r0p1 port. */
#define portINITIAL_EXEC_RETURN ( 0xfffffffd )
/* The systick is a 24-bit counter. */
-#define portMAX_24_BIT_NUMBER ( 0xffffffUL )
+#define portMAX_24_BIT_NUMBER ( 0xffffffUL )
/* A fiddle factor to estimate the number of SysTick counts that would have
occurred while the SysTick counter is stopped during tickless idle
calculations. */
-#define portMISSED_COUNTS_FACTOR ( 45UL )
+#define portMISSED_COUNTS_FACTOR ( 45UL )
+
+/* For strict compliance with the Cortex-M spec the task start address should
+have bit-0 clear, as it is loaded into the PC on exit from an ISR. */
+#define portSTART_ADDRESS_MASK ( ( StackType_t ) 0xfffffffeUL )
/* Each task maintains its own interrupt status in the critical nesting
variable. */
@@ -237,7 +241,7 @@ StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t px
*pxTopOfStack = portINITIAL_XPSR; /* xPSR */
pxTopOfStack--;
- *pxTopOfStack = ( StackType_t ) pxCode; /* PC */
+ *pxTopOfStack = ( ( StackType_t ) pxCode ) & portSTART_ADDRESS_MASK; /* PC */
pxTopOfStack--;
*pxTopOfStack = ( StackType_t ) prvTaskExitError; /* LR */
@@ -564,6 +568,8 @@ void xPortSysTickHandler( void )
/* Enter a critical section but don't use the taskENTER_CRITICAL()
method as that will mask interrupts that should exit sleep mode. */
__disable_irq();
+ __dsb( portSY_FULL_READ_WRITE );
+ __isb( portSY_FULL_READ_WRITE );
/* If a context switch is pending or a task is waiting for the scheduler
to be unsuspended then abandon the low power entry. */
diff --git a/FreeRTOS/Source/portable/RVDS/ARM_CM7/r0p1/port.c b/FreeRTOS/Source/portable/RVDS/ARM_CM7/r0p1/port.c
index 3458eac977..ccefbd9795 100644
--- a/FreeRTOS/Source/portable/RVDS/ARM_CM7/r0p1/port.c
+++ b/FreeRTOS/Source/portable/RVDS/ARM_CM7/r0p1/port.c
@@ -146,6 +146,10 @@ occurred while the SysTick counter is stopped during tickless idle
calculations. */
#define portMISSED_COUNTS_FACTOR ( 45UL )
+/* For strict compliance with the Cortex-M spec the task start address should
+have bit-0 clear, as it is loaded into the PC on exit from an ISR. */
+#define portSTART_ADDRESS_MASK ( ( StackType_t ) 0xfffffffeUL )
+
/* Each task maintains its own interrupt status in the critical nesting
variable. */
static UBaseType_t uxCriticalNesting = 0xaaaaaaaa;
@@ -231,7 +235,7 @@ StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t px
*pxTopOfStack = portINITIAL_XPSR; /* xPSR */
pxTopOfStack--;
- *pxTopOfStack = ( StackType_t ) pxCode; /* PC */
+ *pxTopOfStack = ( ( StackType_t ) pxCode ) & portSTART_ADDRESS_MASK; /* PC */
pxTopOfStack--;
*pxTopOfStack = ( StackType_t ) prvTaskExitError; /* LR */
@@ -346,10 +350,10 @@ BaseType_t xPortStartScheduler( void )
/* Read the value back to see how many bits stuck. */
ucMaxPriorityValue = *pucFirstUserPriorityRegister;
- /* The kernel interrupt priority should be set to the lowest
+ /* The kernel interrupt priority should be set to the lowest
priority. */
configASSERT( ucMaxPriorityValue == ( configKERNEL_INTERRUPT_PRIORITY & ucMaxPriorityValue ) );
-
+
/* Use the same mask on the maximum system call priority. */
ucMaxSysCallPriority = configMAX_SYSCALL_INTERRUPT_PRIORITY & ucMaxPriorityValue;
@@ -550,6 +554,8 @@ void xPortSysTickHandler( void )
/* Enter a critical section but don't use the taskENTER_CRITICAL()
method as that will mask interrupts that should exit sleep mode. */
__disable_irq();
+ __dsb( portSY_FULL_READ_WRITE );
+ __isb( portSY_FULL_READ_WRITE );
/* If a context switch is pending or a task is waiting for the scheduler
to be unsuspended then abandon the low power entry. */
diff --git a/FreeRTOS/Source/portable/Tasking/ARM_CM4F/port.c b/FreeRTOS/Source/portable/Tasking/ARM_CM4F/port.c
index ded132bada..4c95cf49b6 100644
--- a/FreeRTOS/Source/portable/Tasking/ARM_CM4F/port.c
+++ b/FreeRTOS/Source/portable/Tasking/ARM_CM4F/port.c
@@ -105,6 +105,10 @@ debugger. */
#define portTASK_RETURN_ADDRESS prvTaskExitError
#endif
+/* For strict compliance with the Cortex-M spec the task start address should
+have bit-0 clear, as it is loaded into the PC on exit from an ISR. */
+#define portSTART_ADDRESS_MASK ( ( StackType_t ) 0xfffffffeUL )
+
/* The priority used by the kernel is assigned to a variable to make access
from inline assembler easier. */
const uint32_t ulKernelPriority = configKERNEL_INTERRUPT_PRIORITY;
@@ -154,7 +158,7 @@ StackType_t *pxPortInitialiseStack( StackType_t *pxTopOfStack, TaskFunction_t px
*pxTopOfStack = portINITIAL_XPSR; /* xPSR */
pxTopOfStack--;
- *pxTopOfStack = ( StackType_t ) pxCode; /* PC */
+ *pxTopOfStack = ( ( StackType_t ) pxCode ) & portSTART_ADDRESS_MASK; /* PC */
pxTopOfStack--;
*pxTopOfStack = ( StackType_t ) portTASK_RETURN_ADDRESS; /* LR */
diff --git a/FreeRTOS/Source/tasks.c b/FreeRTOS/Source/tasks.c
index 390878af64..7fafd904ac 100644
--- a/FreeRTOS/Source/tasks.c
+++ b/FreeRTOS/Source/tasks.c
@@ -490,7 +490,7 @@ static void prvAddCurrentTaskToDelayedList( TickType_t xTicksToWait, const BaseT
* Searches pxList for a task with name pcNameToQuery - returning a handle to
* the task if it is found, or NULL if the task is not found.
*/
-#if ( INCLUDE_xTaskGetTaskHandle == 1 )
+#if ( INCLUDE_xTaskGetHandle == 1 )
static TCB_t *prvSearchForNameWithinSingleList( List_t *pxList, const char pcNameToQuery[] ) PRIVILEGED_FUNCTION;
@@ -978,6 +978,12 @@ static void prvAddNewTaskToReadyList( TCB_t *pxNewTCB )
mtCOVERAGE_TEST_MARKER();
}
+ /* Increment the uxTaskNumber also so kernel aware debuggers can
+ detect that the task lists need re-generating. This is done before
+ portPRE_TASK_DELETE_HOOK() as in the Windows port that macro will
+ not return. */
+ uxTaskNumber++;
+
if( pxTCB == pxCurrentTCB )
{
/* A task is deleting itself. This cannot complete within the
@@ -991,16 +997,23 @@ static void prvAddNewTaskToReadyList( TCB_t *pxNewTCB )
there is a task that has been deleted and that it should therefore
check the xTasksWaitingTermination list. */
++uxDeletedTasksWaitingCleanUp;
+
+ /* The pre-delete hook is primarily for the Windows simulator,
+ in which Windows specific clean up operations are performed,
+ after which it is not possible to yield away from this task -
+ hence xYieldPending is used to latch that a context switch is
+ required. */
+ portPRE_TASK_DELETE_HOOK( pxTCB, &xYieldPending );
}
else
{
--uxCurrentNumberOfTasks;
prvDeleteTCB( pxTCB );
- }
- /* Increment the uxTaskNumber also so kernel aware debuggers can
- detect that the task lists need re-generating. */
- uxTaskNumber++;
+ /* Reset the next expected unblock time in case it referred to
+ the task that has just been deleted. */
+ prvResetNextTaskUnblockTime();
+ }
traceTASK_DELETE( pxTCB );
}
@@ -1013,24 +1026,11 @@ static void prvAddNewTaskToReadyList( TCB_t *pxNewTCB )
if( pxTCB == pxCurrentTCB )
{
configASSERT( uxSchedulerSuspended == 0 );
-
- /* The pre-delete hook is primarily for the Windows simulator,
- in which Windows specific clean up operations are performed,
- after which it is not possible to yield away from this task -
- hence xYieldPending is used to latch that a context switch is
- required. */
- portPRE_TASK_DELETE_HOOK( pxTCB, &xYieldPending );
portYIELD_WITHIN_API();
}
else
{
- /* Reset the next expected unblock time in case it referred to
- the task that has just been deleted. */
- taskENTER_CRITICAL();
- {
- prvResetNextTaskUnblockTime();
- }
- taskEXIT_CRITICAL();
+ mtCOVERAGE_TEST_MARKER();
}
}
}
@@ -2083,7 +2083,7 @@ TCB_t *pxTCB;
}
/*-----------------------------------------------------------*/
-#if ( INCLUDE_xTaskGetTaskHandle == 1 )
+#if ( INCLUDE_xTaskGetHandle == 1 )
static TCB_t *prvSearchForNameWithinSingleList( List_t *pxList, const char pcNameToQuery[] )
{
@@ -2141,12 +2141,12 @@ TCB_t *pxTCB;
return pxReturn;
}
-#endif /* INCLUDE_xTaskGetTaskHandle */
+#endif /* INCLUDE_xTaskGetHandle */
/*-----------------------------------------------------------*/
-#if ( INCLUDE_xTaskGetTaskHandle == 1 )
+#if ( INCLUDE_xTaskGetHandle == 1 )
- TaskHandle_t xTaskGetTaskHandle( const char *pcNameToQuery ) /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
+ TaskHandle_t xTaskGetHandle( const char *pcNameToQuery ) /*lint !e971 Unqualified char types are allowed for strings and single characters only. */
{
UBaseType_t uxQueue = configMAX_PRIORITIES;
TCB_t* pxTCB;
@@ -2206,7 +2206,7 @@ TCB_t *pxTCB;
return ( TaskHandle_t ) pxTCB;
}
-#endif /* INCLUDE_xTaskGetTaskHandle */
+#endif /* INCLUDE_xTaskGetHandle */
/*-----------------------------------------------------------*/
#if ( configUSE_TRACE_FACILITY == 1 )
@@ -3301,7 +3301,7 @@ static void prvCheckTasksWaitingTermination( void )
#if( configUSE_TRACE_FACILITY == 1 )
- void vTaskGetTaskInfo( TaskHandle_t xTask, TaskStatus_t *pxTaskStatus, BaseType_t xGetFreeStackSpace, eTaskState eState )
+ void vTaskGetInfo( TaskHandle_t xTask, TaskStatus_t *pxTaskStatus, BaseType_t xGetFreeStackSpace, eTaskState eState )
{
TCB_t *pxTCB;
@@ -3406,7 +3406,7 @@ static void prvCheckTasksWaitingTermination( void )
do
{
listGET_OWNER_OF_NEXT_ENTRY( pxNextTCB, pxList );
- vTaskGetTaskInfo( ( TaskHandle_t ) pxNextTCB, &( pxTaskStatusArray[ uxTask ] ), pdTRUE, eState );
+ vTaskGetInfo( ( TaskHandle_t ) pxNextTCB, &( pxTaskStatusArray[ uxTask ] ), pdTRUE, eState );
uxTask++;
} while( pxNextTCB != pxFirstTCB );
}