Common demo tasks:

- Add additional tests to GenQTest.c to test the updated priority inheritance mechanism.
- Slightly increase some delays in recmutex.c to prevent it reporting false errors in high load test cases.

SAMA5D3 Xplained IAR demo:
- Remove space being allocated for stacks that are not used.
- Remove explicit enabling of interrupts in ISR handers as this is now done from the central ISR callback before the individual handers are invoked.
- Reduce both the allocated heap size and the stack allocated to each task.
- Enable I cache.
This commit is contained in:
Richard Barry 2014-08-04 07:53:20 +00:00
parent 47f895cb34
commit 60538c7480
21 changed files with 214 additions and 597 deletions

View File

@ -6,8 +6,8 @@ define symbol __ICFEDIT_region_RAM_start__ = 0x300000;
define symbol __ICFEDIT_region_RAM_end__ = 0x31FFFF;
/*-Sizes-*/
define symbol __ICFEDIT_size_vectors__ = 0x100;
define symbol __ICFEDIT_size_cstack__ = 0x400;
define symbol __ICFEDIT_size_sysstack__ = 0x600;
define symbol __ICFEDIT_size_cstack__ = 0x400;
/*define symbol __ICFEDIT_size_sysstack__ = 0x600; Not used. */
define symbol __ICFEDIT_size_irqstack__ = 0x600;
define symbol __ICFEDIT_size_heap__ = 0x0;
/*-Exports-*/
@ -15,7 +15,7 @@ export symbol __ICFEDIT_region_RAM_start__;
export symbol __ICFEDIT_region_RAM_end__;
export symbol __ICFEDIT_size_vectors__;
export symbol __ICFEDIT_size_cstack__;
export symbol __ICFEDIT_size_sysstack__;
/*export symbol __ICFEDIT_size_sysstack__; Not used. */
export symbol __ICFEDIT_size_irqstack__;
export symbol __ICFEDIT_size_heap__;
/**** End of ICF editor section. ###ICF###*/
@ -25,14 +25,14 @@ define region VEC_region = mem:[from __ICFEDIT_region_RAM_start__ size __ICFEDIT
define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__+__ICFEDIT_size_vectors__ to __ICFEDIT_region_RAM_end__];
define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { };
define block SYS_STACK with alignment = 8, size = __ICFEDIT_size_sysstack__ { };
/* define block SYS_STACK with alignment = 8, size = __ICFEDIT_size_sysstack__ { }; not used. */
define block IRQ_STACK with alignment = 8, size = __ICFEDIT_size_irqstack__ { };
define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { };
initialize by copy with packing=none { readwrite };
initialize by copy with packing=none { readwrite };
do not initialize { readonly section .noinit };
place in VEC_region { section .vectors };
place in RAM_region { readonly };
place in RAM_region { section .cstartup };
place in RAM_region { readwrite, block IRQ_STACK, block SYS_STACK, block CSTACK, block HEAP };
place in RAM_region { readwrite, block IRQ_STACK, /* block SYS_STACK not used, */ block CSTACK, block HEAP };

View File

@ -108,6 +108,7 @@ extern WEAK void LowLevelInit( void )
/* Wait for the PCKRDY1 bit to be set in the PMC_SR register*/
while ((REG_PMC_SR & PMC_SR_PCKRDY1) == 0);
#endif
/* select FIQ */
AIC->AIC_SSR = 0;
AIC->AIC_SVR = (unsigned int) defaultFiqHandler;

View File

@ -186,8 +186,8 @@ uint8_t *pc1, *pc2;
usTemp = ( ( *pc2 ) << 8 ) | *pc1;
return usTemp;
#warning The original code below crashes when build for A5 as endpoint can be misaligned.
//_RB_return endpoint->wMaxPacketSize;
#warning The above code replaces the line below to ensure aborts are not received due to unaligned accesses. Alternatively use the --no_unaligned_access compiler option.
//return endpoint->wMaxPacketSize;
}
/**

View File

@ -124,7 +124,7 @@ extern void USBD_IrqHandler( void );
/*
* The function that creates the CLI task.
*/
void vUARTCommandConsoleStart( uint16_t usStackSize, UBaseType_t uxPriority );
void vUSBCommandConsoleStart( uint16_t usStackSize, UBaseType_t uxPriority );
/*
* Send xDataLength bytes from pcData to the CDC port.
@ -178,7 +178,7 @@ static EventGroupHandle_t xCDCEventBits;
/*-----------------------------------------------------------*/
void vUARTCommandConsoleStart( uint16_t usStackSize, UBaseType_t uxPriority )
void vUSBCommandConsoleStart( uint16_t usStackSize, UBaseType_t uxPriority )
{
/* Event group used to indicate that bytes are available in the Rx buffer
or that bytes have finished sending. */

View File

@ -86,8 +86,8 @@
#define configUSE_IDLE_HOOK 1
#define configUSE_TICK_HOOK 1
#define configMAX_PRIORITIES ( 5 )
#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 160 )
#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 45 * 1024 ) )
#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 150 )
#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 42 * 1024 ) )
#define configMAX_TASK_NAME_LEN ( 10 )
#define configUSE_TRACE_FACILITY 1
#define configUSE_16_BIT_TICKS 0
@ -156,7 +156,7 @@ used. */
and one on TCP/IP). This is done to prevent an output buffer being defined by
each implementation - which would waste RAM. In this case, there is only one
command interpreter running. */
#define configCOMMAND_INT_MAX_OUTPUT_SIZE 2096
#define configCOMMAND_INT_MAX_OUTPUT_SIZE 3000
/* Normal assert() semantics without relying on the provision of an assert.h
header file. */

View File

@ -88,8 +88,6 @@ static void System_Handler( void );
static void System_Handler( void )
{
__enable_interrupt();
/* See the comments above the function prototype in this file. */
FreeRTOS_Tick_Handler();
}

View File

@ -71,15 +71,16 @@
* interrupts. As the interrupt is shared the nesting achieved is not as deep
* as normal when this test is executed, but still worth while.
*
* TC2 channel 0 provides a much higher frequency timer that tests the nesting of
* interrupts that execute above the maximum syscall interrupt priority.
* TC2 channel 0 provides a much higher frequency timer that tests the nesting
* of interrupts that don't use the FreeRTOS API. For convenience, the high
* frequency timer also keeps a count of the number of time it executes, and the
* count is used as the time base for the run time stats (which can be viewed
* through the CLI).
*
* All the timers can nest with the tick interrupt - creating a maximum
* interrupt nesting depth of 3 (normally 4, if the first two timers used
* separate interrupts).
*
* For convenience, the high frequency timer is also used to provide the time
* base for the run time stats.
*/
/* Scheduler includes. */
@ -96,7 +97,6 @@
ensure they don't remain synchronised. The frequency of the highest priority
interrupt is 20 times faster so really hammers the interrupt entry and exit
code. */
#define tmrTIMERS_USED 3
#define tmrTIMER_0_FREQUENCY ( 2000UL )
#define tmrTIMER_1_FREQUENCY ( 2003UL )
#define tmrTIMER_2_FREQUENCY ( 20000UL )
@ -115,7 +115,8 @@ of the lower frequency timers must still be above the tick interrupt priority. *
#define tmrHIGHER_PRIORITY 5
/*-----------------------------------------------------------*/
/* Handlers for the three timer channels. */
/* Handlers for the two timer peripherals - two channels are used in the TC0
timer. */
static void prvTC0_Handler( void );
static void prvTC1_Handler( void );
@ -169,9 +170,6 @@ const uint32_t ulDivider = 128UL, ulTCCLKS = 3UL;
static void prvTC0_Handler( void )
{
#warning Why can interrupts only be enabled inside the C function?
__enable_interrupt();
/* Read will clear the status bit. */
if( ( TC0->TC_CHANNEL[ tmrTC0_CHANNEL_0 ].TC_SR & tmrRC_COMPARE ) != 0 )
{
@ -189,8 +187,6 @@ static void prvTC1_Handler( void )
{
volatile uint32_t ulDummy;
__enable_interrupt();
/* Dummy read to clear status bit. */
ulDummy = TC1->TC_CHANNEL[ tmrTC1_CHANNEL_0 ].TC_SR;

View File

@ -84,13 +84,12 @@
* In addition to the standard demo tasks, the following tasks and tests are
* defined and/or created within this file:
*
* FreeRTOS+CLI command console. The command console is access through the
* UART to USB connector on the _RB_. For
* reasons of robustness testing the UART driver is deliberately written to be
* inefficient and should not be used as a template for a production driver.
* Type "help" to see a list of registered commands. The FreeRTOS+CLI license
* is different to the FreeRTOS license, see http://www.FreeRTOS.org/cli for
* license and usage details. The default baud rate is 115200.
* "FreeRTOS+CLI command console" - The command console is access using the USB
* CDC driver provided by Atmel. It is accessed through the USB connector
* marked J6 SAMA5D3 Xplained board. Type "help" to see a list of registered
* commands. The FreeRTOS+CLI license is different to the FreeRTOS license, see
* http://www.FreeRTOS.org/cli for license and usage details. The default baud
* rate is 115200.
*
* "Reg test" tasks - These fill both the core and floating point registers with
* known values, then check that each register maintains its expected value for
@ -143,12 +142,12 @@
#define mainBLOCK_Q_PRIORITY ( tskIDLE_PRIORITY + 2UL )
#define mainCREATOR_TASK_PRIORITY ( tskIDLE_PRIORITY + 3UL )
#define mainFLOP_TASK_PRIORITY ( tskIDLE_PRIORITY )
#define mainUART_COMMAND_CONSOLE_STACK_SIZE ( configMINIMAL_STACK_SIZE * 3UL )
#define mainCDC_COMMAND_CONSOLE_STACK_SIZE ( configMINIMAL_STACK_SIZE * 2UL )
#define mainCOM_TEST_TASK_PRIORITY ( tskIDLE_PRIORITY + 2 )
#define mainCHECK_TASK_PRIORITY ( configMAX_PRIORITIES - 1 )
#define mainQUEUE_OVERWRITE_PRIORITY ( tskIDLE_PRIORITY )
/* The priority used by the UART command console task. */
/* The initial priority used by the UART command console task. */
#define mainUART_COMMAND_CONSOLE_TASK_PRIORITY ( configMAX_PRIORITIES - 2 )
/* The LED used by the check timer. */
@ -209,7 +208,7 @@ extern void vRegisterSampleCLICommands( void );
/*
* The task that manages the FreeRTOS+CLI input and output.
*/
extern void vUARTCommandConsoleStart( uint16_t usStackSize, UBaseType_t uxPriority );
extern void vUSBCommandConsoleStart( uint16_t usStackSize, UBaseType_t uxPriority );
/*
* A high priority task that does nothing other than execute at a pseudo random
@ -227,7 +226,7 @@ stops incrementing, then an error has been found. */
volatile unsigned long ulRegTest1LoopCounter = 0UL, ulRegTest2LoopCounter = 0UL;
/*-----------------------------------------------------------*/
#warning Check demo and source folders for _RB_
void main_full( void )
{
/* Start all the other standard demo/test tasks. They have not particular
@ -248,7 +247,7 @@ void main_full( void )
/* Start the tasks that implements the command console on the UART, as
described above. */
vUARTCommandConsoleStart( mainUART_COMMAND_CONSOLE_STACK_SIZE, mainUART_COMMAND_CONSOLE_TASK_PRIORITY );
vUSBCommandConsoleStart( mainCDC_COMMAND_CONSOLE_STACK_SIZE, mainUART_COMMAND_CONSOLE_TASK_PRIORITY );
/* Register the standard CLI commands. */
vRegisterSampleCLICommands();

View File

@ -49,7 +49,7 @@
</option>
<option>
<name>MemFile</name>
<state></state>
<state>$TOOLKIT_DIR$\CONFIG\debugger\Atmel\ATSAMA5D35.ddf</state>
</option>
<option>
<name>RunToEnable</name>
@ -1303,7 +1303,7 @@
</plugin>
<plugin>
<file>$TOOLKIT_DIR$\plugins\rtos\OpenRTOS\OpenRTOSPlugin.ewplugin</file>
<loadFlag>0</loadFlag>
<loadFlag>1</loadFlag>
</plugin>
<plugin>
<file>$TOOLKIT_DIR$\plugins\rtos\SafeRTOS\SafeRTOSPlugin.ewplugin</file>

View File

@ -39,20 +39,20 @@
<option>
<name>Input variant</name>
<version>3</version>
<state>6</state>
<state>7</state>
</option>
<option>
<name>Input description</name>
<state>No specifier n, no float nor long long, no scan set, no assignment suppressing.</state>
<state>No specifier n, no float nor long long, no scan set, no assignment suppressing, without multibyte support.</state>
</option>
<option>
<name>Output variant</name>
<version>2</version>
<state>5</state>
<state>7</state>
</option>
<option>
<name>Output description</name>
<state>No specifier a, A, no specifier n, no float nor long long.</state>
<state>No specifier a, A, no specifier n, no float nor long long, no flags.</state>
</option>
<option>
<name>GOutputBinary</name>
@ -1185,9 +1185,6 @@
<name>$PROJ_DIR$\..\..\..\FreeRTOS-Plus\Demo\Common\FreeRTOS_Plus_CLI_Demos\Sample-CLI-commands.c</name>
</file>
</group>
<file>
<name>$PROJ_DIR$\atmel_main.c</name>
</file>
<file>
<name>$PROJ_DIR$\cstartup_with_FreeRTOS_vectors.s</name>
</file>

View File

@ -1,434 +0,0 @@
/* ----------------------------------------------------------------------------
* SAM Software Package License
* ----------------------------------------------------------------------------
* Copyright (c) 2014, Atmel Corporation
*
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* - Redistributions of source code must retain the above copyright notice,
* this list of conditions and the disclaimer below.
*
* Atmel's name may not be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* DISCLAIMER: THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
* DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* ----------------------------------------------------------------------------
*/
/**
* \page getting-started Getting Started with sama5d3 Microcontrollers
*
* \section Purpose
*
* The Getting Started example will help new users get familiar with Atmel's
* sama5d3x microcontroller. This basic application shows the startup
* sequence of a chip and how to use its core peripherals.
*
* \section Requirements
*
* This package can be used with sama5d3 xplained board.
*
* \section Description
*
* The demonstration program makes two LEDs on the board blink at a fixed rate.
* This rate is generated by using Time tick timer. The blinking can be stopped
* using two buttons (one for each LED). If there is no enough buttons on board, please
* type "1" or "2" in the terminal application on PC to control the LEDs
* instead.
*
* \section Usage
*
* -# Build the program and download it inside the xplained board. Please
* refer to the
* <a href="http://www.atmel.com/dyn/resources/prod_documents/6421B.pdf">
* SAM-BA User Guide</a>, the
* <a href="http://www.atmel.com/dyn/resources/prod_documents/doc6310.pdf">
* GNU-Based Software Development</a>
* application note or to the
* <a href="ftp://ftp.iar.se/WWWfiles/arm/Guides/EWARM_UserGuide.ENU.pdf">
* IAR EWARM User Guide</a>,
* depending on your chosen solution.
* -# On the computer, open and configure a terminal application
* (e.g. HyperTerminal on Microsoft Windows) with these settings:
* - 115200 bauds
* - 8 bits of data
* - No parity
* - 1 stop bit
* - No flow control
* -# Start the application.
* -# Two LEDs should start blinking on the board. In the terminal window, the
* following text should appear (values depend on the board and chip used):
* \code
* -- Getting Started Example xxx --
* -- SAMxxxxx-xx
* -- Compiled: xxx xx xxxx xx:xx:xx --
* \endcode
* -# Pressing and release button 1 or type "1" in the terminal application on
* PC should make the first LED stop & restart blinking.
* Pressing and release button 2 or type "1" in the terminal application on
* PC should make the other LED stop & restart blinking.
*
* \section References
* - getting-started/main.c
* - pio.h
* - pio_it.h
* - led.h
* - trace.h
*/
/** \file
*
* This file contains all the specific code for the getting-started example.
*
*/
/*----------------------------------------------------------------------------
* Headers
*----------------------------------------------------------------------------*/
#include "board.h"
#include <stdbool.h>
#include <stdio.h>
/*----------------------------------------------------------------------------
* Local definitions
*----------------------------------------------------------------------------*/
#define NO_PUSHBUTTON
/** IRQ priority for PIO (The lower the value, the greater the priority) */
#define IRQ_PRIOR_PIO 0
/** LED0 blink time, LED1 blink half this time, in ms */
#define BLINK_PERIOD 1000
/** Delay for pushbutton debouncing (in milliseconds). */
#define DEBOUNCE_TIME 500
/*----------------------------------------------------------------------------
* Local variables
*----------------------------------------------------------------------------*/
#ifndef NO_PUSHBUTTON
/** Pushbutton \#1 pin instance. */
const Pin pinPB1 = PIN_PUSHBUTTON_1 ;
/** Pushbutton \#1 pin instance. */
const Pin pinPB2 = PIN_PUSHBUTTON_2 ;
#endif
/** LED0 blinking control. */
volatile bool bLed0Active = true ;
/** LED1 blinking control. */
volatile bool bLed1Active = true ;
/** Global timestamp in milliseconds since start of application */
volatile uint32_t dwTimeStamp = 0;
/*----------------------------------------------------------------------------
* Local functions
*----------------------------------------------------------------------------*/
/**
* \brief Process Buttons Events
*
* Change active states of LEDs when corresponding button events happened.
*/
static void ProcessButtonEvt( uint8_t ucButton )
{
if ( ucButton == 0 )
{
bLed0Active = !bLed0Active ;
if ( !bLed0Active )
{
LED_Clear( 0 );
}
}
else
{
bLed1Active = !bLed1Active ;
/* Enable LED#2 and TC if they were disabled */
if ( bLed1Active )
{
LED_Set( 1 );
TC_Start( TC0, 0 );
}
/* Disable LED#2 and TC if they were enabled */
else
{
LED_Clear( 1 );
TC_Stop( TC0, 0 );
}
}
}
#ifndef NO_PUSHBUTTON
/**
* \brief Handler for Button 1 rising edge interrupt.
*
* Handle process led1 status change.
*/
static void _Button1_Handler( const Pin* pin )
{
pin = pin;
ProcessButtonEvt( 0 ) ;
}
/**
* \brief Handler for Button 2 falling edge interrupt.
*
* Handle process led2 status change.
*/
static void _Button2_Handler( const Pin* pin )
{
pin = pin;
ProcessButtonEvt( 1 ) ;
}
#else
/**
* \brief Handler for DBGU input.
*
* Handle process LED1 or LED2 status change.
*/
static void _DBGU_Handler( void )
{
uint8_t key;
if ( !DBGU_IsRxReady( ) ) return ;
key = DBGU_GetChar( ) ;
switch ( key )
{
case '1': case '2':
ProcessButtonEvt( key - '1' ) ;
break;
}
}
#endif
/**
* \brief Handler for PIT interrupt.
*/
static void _Pit_Handler( void )
{
uint32_t status;
/* Read the PIT status register */
status = PIT_GetStatus() & PIT_SR_PITS;
if (status != 0) {
/* 1 = The Periodic Interval timer has reached PIV since the last read of PIT_PIVR.
Read the PIVR to acknowledge interrupt and get number of ticks
Returns the number of occurrences of periodic intervals since the last read of PIT_PIVR. */
dwTimeStamp += (PIT_GetPIVR() >> 20);
}
}
/**
* \brief Handler for Sysc interrupts.
*/
void _Sysc_Handler( void );
void _Sysc_Handler( void )
{
_Pit_Handler( ) ;
#ifdef NO_PUSHBUTTON
_DBGU_Handler( ) ;
#endif
}
/**
* \brief Configure the periodic interval timer (PIT) to generate an interrupt every
* interrupt every millisecond
*/
static void ConfigurePit(void)
{
PMC->PMC_PCER0 = 1 << ID_PIT;
/* Initialize the PIT to the desired frequency */
PIT_Init(BLINK_PERIOD, BOARD_MCK / 1000000);
/* Configure interrupt on PIT */
IRQ_ConfigureIT(ID_PIT, 0, _Sysc_Handler);
IRQ_EnableIT(ID_PIT);
PIT_EnableIT();
/* Enable the pit */
PIT_Enable();
}
#ifndef NO_PUSHBUTTON
/**
* \brief Configure the Pushbuttons
*
* Configure the PIO as inputs and generate corresponding interrupt when
* pressed or released.
*/
static void _ConfigureButtons( void )
{
/* Configure pios as inputs. */
PIO_Configure( &pinPB1, 1 ) ;
PIO_Configure( &pinPB2, 1 ) ;
/* Adjust pio debounce filter patameters, uses 10 Hz filter. */
PIO_SetDebounceFilter( &pinPB1, 10 ) ;
PIO_SetDebounceFilter( &pinPB1, 10 ) ;
/* Enable PIO controller IRQs. */
PIO_InitializeInterrupts(0);
/* Initialize pios interrupt handlers, see PIO definition in board.h. */
PIO_ConfigureIt(&pinPB1, (void (*)(const Pin *))_Button1_Handler);
PIO_ConfigureIt(&pinPB2, (void (*)(const Pin *))_Button2_Handler);
/* Enable PIO line interrupts. */
PIO_EnableIt( &pinPB1 ) ;
PIO_EnableIt( &pinPB2 ) ;
}
#endif
/**
* \brief Configure LEDs
*
* Configures LEDs \#1 and \#2 (cleared by default).
*/
static void _ConfigureLeds( void )
{
LED_Configure( 0 ) ;
LED_Configure( 1 ) ;
}
/**
* Interrupt handler for TC0 interrupt. Toggles the state of LED\#2.
*/
static void TC0_IrqHandler( void )
{
volatile uint32_t dummy;
/* Clear status bit to acknowledge interrupt */
dummy = TC0->TC_CHANNEL[ 0 ].TC_SR ;
/** Toggle LED state. */
LED_Toggle( 1 ) ;
printf( "2 " ) ;
}
/**
* Configure Timer Counter 0 to generate an interrupt every 250ms.
*/
static void _ConfigureTc( void )
{
uint32_t div;
uint32_t tcclks;
/** Enable peripheral clock. */
PMC->PMC_PCER0 = 1 << ID_TC0;
/** Configure TC for a 4Hz frequency and trigger on RC compare. */
TC_FindMckDivisor( 4, BOARD_MCK, &div, &tcclks, BOARD_MCK );
TC_Configure( TC0, 0, tcclks | TC_CMR_CPCTRG );
TC0->TC_CHANNEL[ 0 ].TC_RC = ( BOARD_MCK / div ) / 4;
/* Configure and enable interrupt on RC compare */
IRQ_ConfigureIT(ID_TC0, 0, TC0_IrqHandler);
TC0->TC_CHANNEL[ 0 ].TC_IER = TC_IER_CPCS;
IRQ_EnableIT(ID_TC0);
/** Start the counter if LED1 is enabled. */
if ( bLed1Active )
{
TC_Start( TC0, 0 );
}
}
/**
* Waits for the given number of milliseconds (using the dwTimeStamp generated
* by the SAM3's microcontrollers's system tick).
* \param delay Delay to wait for, in milliseconds.
*/
static void _Wait( unsigned long delay )
{
volatile uint32_t start = dwTimeStamp;
uint32_t elapsed;
do {
elapsed = dwTimeStamp;
elapsed -= start;
}
while (elapsed < delay);
}
/*----------------------------------------------------------------------------
* Global functions
*----------------------------------------------------------------------------*/
/**
* \brief getting-started Application entry point.
*
* \return Unused (ANSI-C compatibility).
*/
int atmel_main( void );
int atmel_main( void )
{
/* Disable watchdog */
WDT_Disable( WDT ) ;
#if defined (ddram)
MMU_Initialize((uint32_t *)0x30C000);
CP15_EnableMMU();
CP15_EnableDcache();
CP15_EnableIcache();
#endif
/* Output example information */
printf( "-- Getting Started Example %s --\n\r", SOFTPACK_VERSION ) ;
printf( "-- %s\n\r", BOARD_NAME ) ;
printf( "-- Compiled: %s %s --\n\r", __DATE__, __TIME__ ) ;
/* Configure PIT. */
printf( "Configure PIT \n\r" ) ;
//__asm volatile( "cpsid i" );
ConfigurePit() ;
/* PIO configuration for LEDs and Buttons. */
PIO_InitializeInterrupts( IRQ_PRIOR_PIO ) ;
printf( "Configure TC.\n\r" );
_ConfigureTc() ;
printf( "Configure LED PIOs.\n\r" ) ;
_ConfigureLeds() ;
#ifndef NO_PUSHBUTTON
printf( "Configure buttons with debouncing.\n\r" ) ;
_ConfigureButtons() ;
printf( "Press USRBP1 to Start/Stop the blue LED D1 blinking.\n\r" ) ;
printf( "Press USRBP2 to Start/Stop the red LED D2 blinking.\n\r" ) ;
#else
printf( "No push buttons, uses DBG key 1 & 2 instead.\n\r" ) ;
printf( "Press 1 to Start/Stop the blue LED D1 blinking.\n\r" ) ;
printf( "Press 2 to Start/Stop the red LED D2 blinking.\n\r" ) ;
#endif
while ( 1 )
{
/* Wait for LED to be active */
while( !bLed0Active );
/* Toggle LED state if active */
if ( bLed0Active )
{
LED_Toggle( 0 );
printf( "1 " );
}
/* Wait for 500ms */
_Wait(500);
}
}

View File

@ -131,6 +131,8 @@ resetHandler:
/* Perform low-level initialization of the chip using LowLevelInit() */
label:
/* Sets up Supervisor stack before running LowLevelInit. The supervisor
stack is reused by interrupts, which switch from IRQ mode to SVC mode. */
LDR r0, =LowLevelInit
LDR r4, =SFE(CSTACK)
MOV sp, r4
@ -140,14 +142,13 @@ label:
MSR cpsr_c, #ARM_MODE_IRQ | I_BIT | F_BIT ; Change the mode
LDR sp, =SFE(IRQ_STACK)
/* Set up the SVC stack pointer. This allows the stack used by main()
to get reused by interrupts (which switch from IRQ mode to SVC mode). */
MSR cpsr_c, #ARM_MODE_SVC | F_BIT ; Change the mode
LDR sp, =SFE(CSTACK)
/* No need to set up stacks for any other mode as that stack used by
tasks is allocated by FreeRTOS. */
/* Back to Supervisor mode bfore calling main(). The schduduler should
be started from Supervisor mode. */
MSR cpsr_c, #ARM_MODE_SVC | F_BIT ; Change the mode
/* Branch to main() */
LDR r0, =?main
BLX r0

View File

@ -72,7 +72,8 @@
* implemented and described in main_full.c.
*
* This file implements the code that is not demo specific, including the
* hardware setup and FreeRTOS hook functions.
* hardware setup, standard FreeRTOS hook functions, and the ISR hander called
* by the RTOS after interrupt entry (including nesting) has been taken care of.
*
* ENSURE TO READ THE DOCUMENTATION PAGE FOR THIS PORT AND DEMO APPLICATION ON
* THE http://www.FreeRTOS.org WEB SITE FOR FULL INFORMATION ON USING THIS DEMO
@ -80,8 +81,7 @@
*
*/
#warning Remove unused libary files.
#warning document configFPU_D32
#warning Things to document 1) configFPU_D32 setting, 2) flops can't be used in ISRs, 3) Level interrupts need to be cleared in their handling functions 4) Notes on tailoring generic Cortex-A port 5) assert() will hit if CDC is hammered. 6) Barrier instructions in A9 callbacks. 7) In thumb mode the "common sub expression elimination" optimisation cannot be used.
/* Scheduler include files. */
#include "FreeRTOS.h"
@ -125,8 +125,15 @@ void vApplicationIdleHook( void );
void vApplicationStackOverflowHook( TaskHandle_t pxTask, char *pcTaskName );
void vApplicationTickHook( void );
/* Prototype for the IRQ handler called by the generic Cortex-A5 RTOS port
layer. The address of the ISR is passed into this function as a parameter.
Note this level of indirection could be removed by creating a SAMA5 specific
port layer that calls the IRQ directly from the port layer rather than via this
application callback. */
void vApplicationIRQHandler( uint32_t ulInterruptVectorAddress );
/*-----------------------------------------------------------*/
#warning check stack sizes in linker script.
int main( void )
{
/* Configure the hardware ready to run the demo. */
@ -158,6 +165,8 @@ static void prvSetupHardware( void )
/* Configure ports used by LEDs. */
vParTestInitialise();
CP15_EnableIcache();
}
/*-----------------------------------------------------------*/
@ -240,6 +249,31 @@ void vApplicationTickHook( void )
}
#endif
}
/*-----------------------------------------------------------*/
/* The function called by the RTOS port layer after it has managed interrupt
entry. */
void vApplicationIRQHandler( uint32_t ulInterruptVectorAddress )
{
typedef void (*ISRFunction_t)( void );
ISRFunction_t pxISRFunction;
volatile uint32_t * pulAIC_IVR = ( uint32_t * ) configINTERRUPT_VECTOR_ADDRESS;
/* On the SAMA5 the parameter is a pointer to the ISR handling function. */
pxISRFunction = ( ISRFunction_t ) ulInterruptVectorAddress;
/* Write back to the SAMA5's interrupt controller's IVR register in case the
CPU is in protect mode. If the interrupt controller is not in protect mode
then this write is not necessary. */
*pulAIC_IVR = 0;
/* Ensure the write takes before re-enabling interrupts. */
__DSB();
__ISB();
__enable_irq();
/* Call the installed ISR. */
pxISRFunction();
}

View File

@ -6,20 +6,20 @@
<Debug-Log>
<ColumnWidth0>20</ColumnWidth0><ColumnWidth1>1622</ColumnWidth1></Debug-Log>
<PreferedWindows><Position>3</Position><ScreenPosX>0</ScreenPosX><ScreenPosY>0</ScreenPosY><Windows><Window><Factory>Build</Factory></Window><Window><Factory>Find-in-Files</Factory></Window></Windows></PreferedWindows><ColumnWidth0>20</ColumnWidth0><ColumnWidth1>1622</ColumnWidth1></Debug-Log>
<Build>
<ColumnWidth0>20</ColumnWidth0><ColumnWidth1>1216</ColumnWidth1><ColumnWidth2>324</ColumnWidth2><ColumnWidth3>81</ColumnWidth3></Build>
<ColumnWidth0>20</ColumnWidth0><ColumnWidth1>1216</ColumnWidth1><ColumnWidth2>324</ColumnWidth2><ColumnWidth3>81</ColumnWidth3><PreferedWindows><Position>3</Position><ScreenPosX>0</ScreenPosX><ScreenPosY>0</ScreenPosY><Windows><Window><Factory>Debug-Log</Factory></Window><Window><Factory>Find-in-Files</Factory></Window></Windows></PreferedWindows></Build>
<Workspace>
<ColumnWidths>
<Column0>258</Column0><Column1>27</Column1><Column2>27</Column2><Column3>27</Column3></ColumnWidths>
<Column0>242</Column0><Column1>27</Column1><Column2>27</Column2><Column3>27</Column3></ColumnWidths>
</Workspace>
<Disassembly>
<col-names>
@ -30,32 +30,16 @@
<item>500</item><item>20</item></col-widths>
<DisasmHistory><item>0x0030211C</item><item>0x00302750</item></DisasmHistory>
<DisasmHistory><item>0x305444</item><item>0x0030211C</item><item>0x00302750</item></DisasmHistory>
<PreferedWindows><Position>2</Position><ScreenPosX>0</ScreenPosX><ScreenPosY>0</ScreenPosY><Windows/></PreferedWindows><ShowCodeCoverage>1</ShowCodeCoverage><ShowInstrProfiling>1</ShowInstrProfiling></Disassembly>
<Register><PreferedWindows><Position>2</Position><ScreenPosX>0</ScreenPosX><ScreenPosY>0</ScreenPosY><Windows/></PreferedWindows></Register><WATCH_1><expressions><item></item></expressions><col-names><item>Expression</item><item>Location</item><item>Type</item><item>Value</item></col-names><col-widths><item>207</item><item>150</item><item>100</item><item>294</item></col-widths><PreferedWindows><Position>2</Position><ScreenPosX>0</ScreenPosX><ScreenPosY>0</ScreenPosY><Windows/></PreferedWindows></WATCH_1><CallStack><PreferedWindows><Position>1</Position><ScreenPosX>0</ScreenPosX><ScreenPosY>0</ScreenPosY><Windows/></PreferedWindows><col-names><item>Frame</item><item>_I0</item></col-names><col-widths><item>400</item><item>20</item></col-widths></CallStack><Breakpoints><PreferedWindows><Position>3</Position><ScreenPosX>0</ScreenPosX><ScreenPosY>0</ScreenPosY><Windows/></PreferedWindows><col-names><item>Breakpoint</item><item>_I0</item></col-names><col-widths><item>500</item><item>35</item></col-widths></Breakpoints><Find-in-Files><ColumnWidth0>497</ColumnWidth0><ColumnWidth1>82</ColumnWidth1><ColumnWidth2>746</ColumnWidth2><ColumnWidth3>331</ColumnWidth3></Find-in-Files><QuickWatch><PreferedWindows><Position>2</Position><ScreenPosX>0</ScreenPosX><ScreenPosY>0</ScreenPosY><Windows/></PreferedWindows><col-names><item>Expression</item><item>Location</item><item>Type</item><item>Value</item></col-names><col-widths><item>100</item><item>150</item><item>100</item><item>100</item></col-widths><QWatchHistory><item>TC0</item><item>TC0-&gt;TC_CHANNEL[ tmrTC0_CHANNEL_0 ].TC_RC</item></QWatchHistory></QuickWatch></Static>
<Register><PreferedWindows><Position>2</Position><ScreenPosX>0</ScreenPosX><ScreenPosY>0</ScreenPosY><Windows/></PreferedWindows></Register><WATCH_1><expressions><item></item></expressions><col-names><item>Expression</item><item>Location</item><item>Type</item><item>Value</item></col-names><col-widths><item>207</item><item>150</item><item>100</item><item>294</item></col-widths><PreferedWindows><Position>2</Position><ScreenPosX>0</ScreenPosX><ScreenPosY>0</ScreenPosY><Windows/></PreferedWindows></WATCH_1><CallStack><PreferedWindows><Position>1</Position><ScreenPosX>0</ScreenPosX><ScreenPosY>0</ScreenPosY><Windows/></PreferedWindows><col-names><item>Frame</item><item>_I0</item></col-names><col-widths><item>400</item><item>20</item></col-widths></CallStack><Breakpoints><PreferedWindows><Position>3</Position><ScreenPosX>0</ScreenPosX><ScreenPosY>0</ScreenPosY><Windows/></PreferedWindows><col-names><item>Breakpoint</item><item>_I0</item></col-names><col-widths><item>500</item><item>35</item></col-widths></Breakpoints><Find-in-Files><ColumnWidth0>497</ColumnWidth0><ColumnWidth1>82</ColumnWidth1><ColumnWidth2>746</ColumnWidth2><ColumnWidth3>331</ColumnWidth3><PreferedWindows><Position>3</Position><ScreenPosX>0</ScreenPosX><ScreenPosY>0</ScreenPosY><Windows><Window><Factory>Debug-Log</Factory></Window><Window><Factory>Build</Factory></Window></Windows></PreferedWindows></Find-in-Files><QuickWatch><PreferedWindows><Position>2</Position><ScreenPosX>0</ScreenPosX><ScreenPosY>0</ScreenPosY><Windows/></PreferedWindows><col-names><item>Expression</item><item>Location</item><item>Type</item><item>Value</item></col-names><col-widths><item>100</item><item>150</item><item>100</item><item>100</item></col-widths><QWatchHistory><item>TC0</item><item>TC0-&gt;TC_CHANNEL[ tmrTC0_CHANNEL_0 ].TC_RC</item></QWatchHistory></QuickWatch><Memory><PreferedWindows><Position>3</Position><ScreenPosX>0</ScreenPosX><ScreenPosY>0</ScreenPosY><Windows/></PreferedWindows><FindDirection>1</FindDirection><FindAsHex>0</FindAsHex></Memory><TASKVIEW><Column0>200</Column0><Column1>100</Column1><Column2>100</Column2><Column3>100</Column3><Column4>100</Column4><Column5>100</Column5><Column6>100</Column6><Column7>100</Column7><Column8>150</Column8></TASKVIEW><QUEUEVIEW><Column0>200</Column0><Column1>100</Column1><Column2>100</Column2><Column3>100</Column3><Column4>100</Column4><Column5>100</Column5><Column6>100</Column6></QUEUEVIEW></Static>
<Windows>
<Wnd1>
<Tabs>
<Tab>
<Identity>TabID-13925-23874</Identity>
<TabName>Debug Log</TabName>
<Factory>Debug-Log</Factory>
<Session/>
</Tab>
<Tab>
<Identity>TabID-13402-23884</Identity>
<TabName>Build</TabName>
<Factory>Build</Factory>
<Session/>
</Tab>
<Tab><Identity>TabID-21109-11091</Identity><TabName>Find in Files</TabName><Factory>Find-in-Files</Factory><Session/></Tab></Tabs>
<SelectedTab>0</SelectedTab></Wnd1><Wnd2>
<Tabs>
<Tab>
<Identity>TabID-24673-23877</Identity>
@ -63,24 +47,24 @@
<Factory>Workspace</Factory>
<Session>
<NodeDict><ExpandedNode>RTOSDemo</ExpandedNode><ExpandedNode>RTOSDemo/Full Demo</ExpandedNode></NodeDict></Session>
<NodeDict><ExpandedNode>RTOSDemo</ExpandedNode><ExpandedNode>RTOSDemo/Atmel Files</ExpandedNode><ExpandedNode>RTOSDemo/Atmel Files/libchip_sama5d3x</ExpandedNode><ExpandedNode>RTOSDemo/FreeRTOS Source</ExpandedNode><ExpandedNode>RTOSDemo/FreeRTOS Source/portable</ExpandedNode><ExpandedNode>RTOSDemo/FreeRTOS Source/portable/MemMang</ExpandedNode><ExpandedNode>RTOSDemo/FreeRTOS+CLI</ExpandedNode><ExpandedNode>RTOSDemo/Full Demo</ExpandedNode><ExpandedNode>RTOSDemo/Full Demo/Common Demo Tasks</ExpandedNode></NodeDict></Session>
</Tab>
</Tabs>
<SelectedTab>0</SelectedTab></Wnd2></Windows>
<SelectedTab>0</SelectedTab></Wnd1><Wnd2><Tabs><Tab><Identity>TabID-22902-32031</Identity><TabName>Tasks</TabName><Factory>TASKVIEW</Factory><Session/></Tab></Tabs><SelectedTab>0</SelectedTab></Wnd2><Wnd3><Tabs><Tab><Identity>TabID-22379-32041</Identity><TabName>Queues</TabName><Factory>QUEUEVIEW</Factory><Session/></Tab></Tabs><SelectedTab>0</SelectedTab></Wnd3></Windows>
<Editor>
<Pane><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\Full_Demo\main_full.c</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>370</YPos2><SelStart2>15067</SelStart2><SelEnd2>15067</SelEnd2></Tab><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\AtmelFiles\usb\common\core\USBDescriptors.c</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>165</YPos2><SelStart2>6026</SelStart2><SelEnd2>6026</SelEnd2></Tab><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\main.c</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>109</YPos2><SelStart2>6007</SelStart2><SelEnd2>6007</SelEnd2></Tab><ActiveTab>2</ActiveTab><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\CDCCommandConsole.c</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>309</YPos2><SelStart2>11984</SelStart2><SelEnd2>11984</SelEnd2></Tab><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\Full_Demo\IntQueueTimer.c</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>162</YPos2><SelStart2>8098</SelStart2><SelEnd2>8116</SelEnd2></Tab><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\..\..\Source\tasks.c</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>1561</YPos2><SelStart2>55424</SelStart2><SelEnd2>55424</SelEnd2></Tab><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\..\..\Source\portable\IAR\ARM_CA5_No_GIC\portmacro.h</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>107</YPos2><SelStart2>5219</SelStart2><SelEnd2>5219</SelEnd2></Tab></Pane><ActivePane>0</ActivePane><Sizes><Pane><X>1000000</X><Y>1000000</Y></Pane></Sizes><SplitMode>1</SplitMode></Editor>
<Pane><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\main.c</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>140</YPos2><SelStart2>7249</SelStart2><SelEnd2>7249</SelEnd2></Tab><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\Full_Demo\main_full.c</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>63</YPos2><SelStart2>0</SelStart2><SelEnd2>0</SelEnd2></Tab><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\blinky_demo\main_blinky.c</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>63</YPos2><SelStart2>1373</SelStart2><SelEnd2>1373</SelEnd2></Tab><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\..\..\Source\portable\IAR\ARM_CA5_No_GIC\portASM.s</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>73</YPos2><SelStart2>3799</SelStart2><SelEnd2>3799</SelEnd2></Tab><ActiveTab>3</ActiveTab></Pane><ActivePane>0</ActivePane><Sizes><Pane><X>1000000</X><Y>1000000</Y></Pane></Sizes><SplitMode>1</SplitMode></Editor>
<Positions>
<Top><Row0><Sizes><Toolbar-0104A108><key>iaridepm.enu1</key></Toolbar-0104A108></Sizes></Row0><Row1><Sizes><Toolbar-16133258><key>debuggergui.enu1</key></Toolbar-16133258></Sizes></Row1></Top><Left><Row0><Sizes><Wnd2><Rect><Top>-2</Top><Left>-2</Left><Bottom>718</Bottom><Right>332</Right><x>-2</x><y>-2</y><xscreen>200</xscreen><yscreen>200</yscreen><sizeHorzCX>119048</sizeHorzCX><sizeHorzCY>203252</sizeHorzCY><sizeVertCX>198810</sizeVertCX><sizeVertCY>731707</sizeVertCY></Rect></Wnd2></Sizes></Row0></Left><Right><Row0><Sizes/></Row0></Right><Bottom><Row0><Sizes><Wnd1><Rect><Top>-2</Top><Left>-2</Left><Bottom>198</Bottom><Right>1682</Right><x>-2</x><y>-2</y><xscreen>1684</xscreen><yscreen>200</yscreen><sizeHorzCX>1002381</sizeHorzCX><sizeHorzCY>203252</sizeHorzCY><sizeVertCX>119048</sizeVertCX><sizeVertCY>203252</sizeVertCY></Rect></Wnd1></Sizes></Row0></Bottom><Float><Sizes/></Float></Positions>
<Top><Row0><Sizes><Toolbar-0111A108><key>iaridepm.enu1</key></Toolbar-0111A108></Sizes></Row0><Row1><Sizes><Toolbar-222ED2A8><key>debuggergui.enu1</key></Toolbar-222ED2A8></Sizes></Row1></Top><Left><Row0><Sizes><Wnd1><Rect><Top>-2</Top><Left>-2</Left><Bottom>520</Bottom><Right>332</Right><x>-2</x><y>-2</y><xscreen>200</xscreen><yscreen>200</yscreen><sizeHorzCX>119048</sizeHorzCX><sizeHorzCY>203252</sizeHorzCY><sizeVertCX>198810</sizeVertCX><sizeVertCY>530488</sizeVertCY></Rect></Wnd1></Sizes></Row0></Left><Right><Row0><Sizes/></Row0></Right><Bottom><Row0><Sizes><Wnd2><Rect><Top>-2</Top><Left>-2</Left><Bottom>198</Bottom><Right>1682</Right><x>-2</x><y>-2</y><xscreen>1684</xscreen><yscreen>200</yscreen><sizeHorzCX>1002381</sizeHorzCX><sizeHorzCY>203252</sizeHorzCY><sizeVertCX>119048</sizeVertCX><sizeVertCY>203252</sizeVertCY></Rect></Wnd2></Sizes></Row0><Row1><Sizes><Wnd3><Rect><Top>196</Top><Left>-2</Left><Bottom>396</Bottom><Right>1682</Right><x>-2</x><y>196</y><xscreen>1684</xscreen><yscreen>200</yscreen><sizeHorzCX>1002381</sizeHorzCX><sizeHorzCY>203252</sizeHorzCY><sizeVertCX>119048</sizeVertCX><sizeVertCY>203252</sizeVertCY></Rect></Wnd3></Sizes></Row1></Bottom><Float><Sizes/></Float></Positions>
</Desktop>
</Project>

View File

@ -14,7 +14,7 @@ Watch0=_ 0 "" 0 "" 0 "" 0 "" 0 0 0 0
Watch1=_ 0 "" 0 "" 0 "" 0 "" 0 0 0 0
CStepIntDis=_ 0
[DebugChecksum]
Checksum=1546321988
Checksum=-666464609
[Exceptions]
StopOnUncaught=_ 0
StopOnThrow=_ 0
@ -42,7 +42,7 @@ Exclusions=
[Disassemble mode]
mode=0
[Breakpoints2]
Bp0=_ 1 "EMUL_CODE" "{$PROJ_DIR$\main.c}.214.2" 0 0 1 "" 0 "" 0
Bp0=_ 1 "EMUL_CODE" "{$PROJ_DIR$\main.c}.218.24" 0 0 1 "" 0 "" 0
Count=1
[Aliases]
Count=0

View File

@ -36,7 +36,7 @@
<Windows>
<Wnd2>
<Wnd1>
<Tabs>
<Tab>
<Identity>TabID-22351-19008</Identity>
@ -44,11 +44,11 @@
<Factory>Workspace</Factory>
<Session>
<NodeDict><ExpandedNode>RTOSDemo</ExpandedNode><ExpandedNode>RTOSDemo/FreeRTOS Source</ExpandedNode><ExpandedNode>RTOSDemo/FreeRTOS Source/portable</ExpandedNode><ExpandedNode>RTOSDemo/Full Demo</ExpandedNode></NodeDict></Session>
<NodeDict><ExpandedNode>RTOSDemo</ExpandedNode></NodeDict></Session>
</Tab>
</Tabs>
<SelectedTab>0</SelectedTab></Wnd2><Wnd3>
<SelectedTab>0</SelectedTab></Wnd1><Wnd4>
<Tabs>
<Tab>
<Identity>TabID-21076-19237</Identity>
@ -58,20 +58,20 @@
</Tab>
<Tab><Identity>TabID-23502-23081</Identity><TabName>Debug Log</TabName><Factory>Debug-Log</Factory><Session/></Tab><Tab><Identity>TabID-24431-23894</Identity><TabName>Ambiguous Definitions</TabName><Factory>Select-Ambiguous-Definitions</Factory><Session/></Tab><Tab><Identity>TabID-9033-6116</Identity><TabName>Find in Files</TabName><Factory>Find-in-Files</Factory><Session/></Tab></Tabs>
<SelectedTab>0</SelectedTab></Wnd3></Windows>
<SelectedTab>0</SelectedTab></Wnd4></Windows>
<Editor>
<Pane><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\Full_Demo\main_full.c</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>370</YPos2><SelStart2>15067</SelStart2><SelEnd2>15067</SelEnd2></Tab><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\AtmelFiles\usb\common\core\USBDescriptors.c</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>165</YPos2><SelStart2>6026</SelStart2><SelEnd2>6026</SelEnd2></Tab><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\main.c</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>109</YPos2><SelStart2>6007</SelStart2><SelEnd2>6007</SelEnd2></Tab><ActiveTab>2</ActiveTab><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\CDCCommandConsole.c</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>309</YPos2><SelStart2>11984</SelStart2><SelEnd2>11984</SelEnd2></Tab><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\Full_Demo\IntQueueTimer.c</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>162</YPos2><SelStart2>8098</SelStart2><SelEnd2>8116</SelEnd2></Tab><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\..\..\Source\tasks.c</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>1561</YPos2><SelStart2>55424</SelStart2><SelEnd2>55424</SelEnd2></Tab><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\..\..\Source\portable\IAR\ARM_CA5_No_GIC\portmacro.h</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>107</YPos2><SelStart2>5219</SelStart2><SelEnd2>5219</SelEnd2></Tab></Pane><ActivePane>0</ActivePane><Sizes><Pane><X>1000000</X><Y>1000000</Y></Pane></Sizes><SplitMode>1</SplitMode></Editor>
<Pane><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\main.c</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>59</YPos2><SelStart2>7249</SelStart2><SelEnd2>7249</SelEnd2></Tab><ActiveTab>0</ActiveTab><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\Full_Demo\main_full.c</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>63</YPos2><SelStart2>0</SelStart2><SelEnd2>0</SelEnd2></Tab><Tab><Factory>TextEditor</Factory><Filename>$WS_DIR$\blinky_demo\main_blinky.c</Filename><XPos>0</XPos><YPos>0</YPos><SelStart>0</SelStart><SelEnd>0</SelEnd><XPos2>0</XPos2><YPos2>63</YPos2><SelStart2>1373</SelStart2><SelEnd2>1373</SelEnd2></Tab></Pane><ActivePane>0</ActivePane><Sizes><Pane><X>1000000</X><Y>1000000</Y></Pane></Sizes><SplitMode>1</SplitMode></Editor>
<Positions>
<Top><Row0><Sizes><Toolbar-0104A108><key>iaridepm.enu1</key></Toolbar-0104A108></Sizes></Row0><Row1><Sizes/></Row1></Top><Left><Row0><Sizes><Wnd2><Rect><Top>-2</Top><Left>-2</Left><Bottom>668</Bottom><Right>352</Right><x>-2</x><y>-2</y><xscreen>190</xscreen><yscreen>170</yscreen><sizeHorzCX>113095</sizeHorzCX><sizeHorzCY>172764</sizeHorzCY><sizeVertCX>210714</sizeVertCX><sizeVertCY>680894</sizeVertCY></Rect></Wnd2></Sizes></Row0></Left><Right><Row0><Sizes/></Row0></Right><Bottom><Row0><Sizes><Wnd3><Rect><Top>-2</Top><Left>-2</Left><Bottom>272</Bottom><Right>1682</Right><x>-2</x><y>-2</y><xscreen>1684</xscreen><yscreen>274</yscreen><sizeHorzCX>1002381</sizeHorzCX><sizeHorzCY>278455</sizeHorzCY><sizeVertCX>113095</sizeVertCX><sizeVertCY>172764</sizeVertCY></Rect></Wnd3></Sizes></Row0></Bottom><Float><Sizes/></Float></Positions>
<Top><Row0><Sizes><Toolbar-0111A108><key>iaridepm.enu1</key></Toolbar-0111A108></Sizes></Row0></Top><Left><Row0><Sizes><Wnd1><Rect><Top>-2</Top><Left>-2</Left><Bottom>668</Bottom><Right>352</Right><x>-2</x><y>-2</y><xscreen>190</xscreen><yscreen>170</yscreen><sizeHorzCX>113095</sizeHorzCX><sizeHorzCY>172764</sizeHorzCY><sizeVertCX>210714</sizeVertCX><sizeVertCY>680894</sizeVertCY></Rect></Wnd1></Sizes></Row0></Left><Right><Row0><Sizes/></Row0></Right><Bottom><Row0><Sizes><Wnd4><Rect><Top>-2</Top><Left>-2</Left><Bottom>272</Bottom><Right>1682</Right><x>-2</x><y>-2</y><xscreen>1684</xscreen><yscreen>274</yscreen><sizeHorzCX>1002381</sizeHorzCX><sizeHorzCY>278455</sizeHorzCY><sizeVertCX>113095</sizeVertCX><sizeVertCY>172764</sizeVertCY></Rect></Wnd4></Sizes></Row0></Bottom><Float><Sizes/></Float></Positions>
</Desktop>
</Workspace>

View File

@ -413,7 +413,7 @@ QueueHandle_t xQueue;
static void prvLowPriorityMutexTask( void *pvParameters )
{
SemaphoreHandle_t xMutex = ( SemaphoreHandle_t ) pvParameters;
SemaphoreHandle_t xMutex = ( SemaphoreHandle_t ) pvParameters, xLocalMutex;
#ifdef USE_STDIO
void vPrintDisplayMessage( const char * const * ppcMessageToSend );
@ -424,6 +424,10 @@ SemaphoreHandle_t xMutex = ( SemaphoreHandle_t ) pvParameters;
vPrintDisplayMessage( &pcTaskStartMsg );
#endif
/* The local mutex is used to check the 'mutexs held' count. */
xLocalMutex = xSemaphoreCreateMutex();
configASSERT( xLocalMutex );
for( ;; )
{
/* Take the mutex. It should be available now. */
@ -432,10 +436,10 @@ SemaphoreHandle_t xMutex = ( SemaphoreHandle_t ) pvParameters;
xErrorDetected = pdTRUE;
}
/* Set our guarded variable to a known start value. */
/* Set the guarded variable to a known start value. */
ulGuardedVariable = 0;
/* Our priority should be as per that assigned when the task was
/* This task's priority should be as per that assigned when the task was
created. */
if( uxTaskPriorityGet( NULL ) != genqMUTEX_LOW_PRIORITY )
{
@ -450,7 +454,7 @@ SemaphoreHandle_t xMutex = ( SemaphoreHandle_t ) pvParameters;
taskYIELD();
#endif
/* Ensure the task is reporting it priority as blocked and not
/* Ensure the task is reporting its priority as blocked and not
suspended (as it would have done in versions up to V7.5.3). */
#if( INCLUDE_eTaskGetState == 1 )
{
@ -458,37 +462,46 @@ SemaphoreHandle_t xMutex = ( SemaphoreHandle_t ) pvParameters;
}
#endif /* INCLUDE_eTaskGetState */
/* We should now have inherited the prioritoy of the high priority task,
/* The priority of the high priority task should now have been inherited
as by now it will have attempted to get the mutex. */
if( uxTaskPriorityGet( NULL ) != genqMUTEX_HIGH_PRIORITY )
{
xErrorDetected = pdTRUE;
}
/* We can attempt to set our priority to the test priority - between the
idle priority and the medium/high test priorities, but our actual
prioroity should remain at the high priority. */
/* Attempt to set the priority of this task to the test priority -
between the idle priority and the medium/high test priorities, but the
actual priority should remain at the high priority. */
vTaskPrioritySet( NULL, genqMUTEX_TEST_PRIORITY );
if( uxTaskPriorityGet( NULL ) != genqMUTEX_HIGH_PRIORITY )
{
xErrorDetected = pdTRUE;
}
/* Now unsuspend the medium priority task. This should not run as our
inherited priority is above that of the medium priority task. */
/* Now unsuspend the medium priority task. This should not run as the
inherited priority of this task is above that of the medium priority
task. */
vTaskResume( xMediumPriorityMutexTask );
/* If the did run then it will have incremented our guarded variable. */
/* If the medium priority task did run then it will have incremented the
guarded variable. */
if( ulGuardedVariable != 0 )
{
xErrorDetected = pdTRUE;
}
/* When we give back the semaphore our priority should be disinherited
back to the priority to which we attempted to set ourselves. This means
that when the high priority task next blocks, the medium priority task
should execute and increment the guarded variable. When we next run
both the high and medium priority tasks will have been suspended again. */
/* Take the local mutex too, so two mutexes are now held. */
if( xSemaphoreTake( xLocalMutex, genqNO_BLOCK ) != pdPASS )
{
xErrorDetected = pdTRUE;
}
/* When the semaphore is given back the priority of this task should not
yet be disinherited because the local mutex is still held. This is a
simplification to allow FreeRTOS to be integrated with middleware that
attempts to hold multiple mutexes without bloating the code with complex
algorithms. It is possible that the high priority mutex task will
execute as it shares a priority with this task. */
if( xSemaphoreGive( xMutex ) != pdPASS )
{
xErrorDetected = pdTRUE;
@ -498,24 +511,52 @@ SemaphoreHandle_t xMutex = ( SemaphoreHandle_t ) pvParameters;
taskYIELD();
#endif
/* Check that the guarded variable did indeed increment... */
/* The guarded variable is only incremented by the medium priority task,
which still should not have executed as this task should remain at the
higher priority, ensure this is the case. */
if( ulGuardedVariable != 0 )
{
xErrorDetected = pdTRUE;
}
if( uxTaskPriorityGet( NULL ) != genqMUTEX_HIGH_PRIORITY )
{
xErrorDetected = pdTRUE;
}
/* Now also give back the local mutex, taking the held count back to 0.
This time the priority of this task should be disinherited back to the
priority to which it was set while the mutex was held. This means
the medium priority task should execute and increment the guarded
variable. When this task next runs both the high and medium priority
tasks will have been suspended again. */
if( xSemaphoreGive( xLocalMutex ) != pdPASS )
{
xErrorDetected = pdTRUE;
}
#if configUSE_PREEMPTION == 0
taskYIELD();
#endif
/* Check the guarded variable did indeed increment... */
if( ulGuardedVariable != 1 )
{
xErrorDetected = pdTRUE;
}
/* ... and that our priority has been disinherited to
/* ... and that the priority of this task has been disinherited to
genqMUTEX_TEST_PRIORITY. */
if( uxTaskPriorityGet( NULL ) != genqMUTEX_TEST_PRIORITY )
{
xErrorDetected = pdTRUE;
}
/* Set our priority back to our original priority ready for the next
loop around this test. */
/* Set the priority of this task back to its original value, ready for
the next loop around this test. */
vTaskPrioritySet( NULL, genqMUTEX_LOW_PRIORITY );
/* Just to show we are still running. */
/* Just to show this task is still running. */
ulLoopCounter2++;
#if configUSE_PREEMPTION == 0
@ -561,8 +602,8 @@ SemaphoreHandle_t xMutex = ( SemaphoreHandle_t ) pvParameters;
xErrorDetected = pdTRUE;
}
/* When we eventually obtain the mutex we just give it back then
return to suspend ready for the next test. */
/* When the mutex is eventually obtained it is just given back before
returning to suspend ready for the next cycle. */
if( xSemaphoreGive( xMutex ) != pdPASS )
{
xErrorDetected = pdTRUE;

View File

@ -1,5 +1,5 @@
/*
FreeRTOS V8.0.1 - Copyright (C) 2014 Real Time Engineers Ltd.
FreeRTOS V8.0.1 - Copyright (C) 2014 Real Time Engineers Ltd.
All rights reserved
VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
@ -135,7 +135,7 @@ from within the interrupts. */
#define timerNORMALLY_EMPTY_TX() \
if( xQueueIsQueueFullFromISR( xNormallyEmptyQueue ) != pdTRUE ) \
{ \
UBaseType_t uxSavedInterruptStatus; \
UBaseType_t uxSavedInterruptStatus; \
uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); \
{ \
uxValueForNormallyEmptyQueue++; \
@ -149,7 +149,7 @@ from within the interrupts. */
#define timerNORMALLY_FULL_TX() \
if( xQueueIsQueueFullFromISR( xNormallyFullQueue ) != pdTRUE ) \
{ \
UBaseType_t uxSavedInterruptStatus; \
UBaseType_t uxSavedInterruptStatus; \
uxSavedInterruptStatus = portSET_INTERRUPT_MASK_FROM_ISR(); \
{ \
uxValueForNormallyFullQueue++; \

View File

@ -1,5 +1,5 @@
/*
FreeRTOS V8.0.1 - Copyright (C) 2014 Real Time Engineers Ltd.
FreeRTOS V8.0.1 - Copyright (C) 2014 Real Time Engineers Ltd.
All rights reserved
VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
@ -210,7 +210,7 @@ static void prvTimerTestTask( void *pvParameters )
/* Check the auto reload timers can be stopped correctly, and correctly
report their state. */
prvTest4_CheckAutoReloadTimersCanBeStopped();
/* Check the one shot timer only calls its callback once after it has been
started, and that it reports its state correctly. */
prvTest5_CheckBasicOneShotTimerBehaviour();
@ -238,7 +238,7 @@ static TickType_t xIterationsWithoutCounterIncrement = ( TickType_t ) 0, xLastCy
elsewhere. Start counting Iterations again. */
xIterationsWithoutCounterIncrement = ( TickType_t ) 0;
xLastCycleFrequency = xCycleFrequency;
}
}
/* Calculate the maximum number of times that it is permissible for this
function to be called without ulLoopCounter being incremented. This is
@ -336,7 +336,7 @@ UBaseType_t xTimer;
configASSERT( xTestStatus );
}
}
/* Create the timers that are used from the tick interrupt to test the timer
API functions that can be called from an ISR. */
xISRAutoReloadTimer = xTimerCreate( "ISR AR", /* The text name given to the timer. */
@ -350,7 +350,7 @@ UBaseType_t xTimer;
pdFALSE, /* This is a one shot timer. */
( void * ) NULL, /* The identifier is not required. */
prvISROneShotTimerCallback ); /* The callback that is executed when the timer expires. */
if( ( xISRAutoReloadTimer == NULL ) || ( xISROneShotTimer == NULL ) )
{
xTestStatus = pdFAIL;
@ -394,13 +394,13 @@ TickType_t xBlockPeriod, xTimerPeriod, xExpectedNumber;
/* Check the auto reload timers expire at the expected rates. */
/* Delaying for configTIMER_QUEUE_LENGTH * xBasePeriod ticks should allow
all the auto reload timers to expire at least once. */
xBlockPeriod = ( ( TickType_t ) configTIMER_QUEUE_LENGTH ) * xBasePeriod;
vTaskDelay( xBlockPeriod );
/* Check that all the auto reload timers have called their callback
/* Check that all the auto reload timers have called their callback
function the expected number of times. */
for( ucTimer = 0; ucTimer < ( uint8_t ) configTIMER_QUEUE_LENGTH; ucTimer++ )
{
@ -408,7 +408,7 @@ TickType_t xBlockPeriod, xTimerPeriod, xExpectedNumber;
by the timer period. */
xTimerPeriod = ( ( ( TickType_t ) ucTimer + ( TickType_t ) 1 ) * xBasePeriod );
xExpectedNumber = xBlockPeriod / xTimerPeriod;
ucMaxAllowableValue = ( ( uint8_t ) xExpectedNumber ) ;
ucMinAllowableValue = ( uint8_t ) ( ( uint8_t ) xExpectedNumber - ( uint8_t ) 1 ); /* Weird casting to try and please all compilers. */
@ -431,7 +431,7 @@ TickType_t xBlockPeriod, xTimerPeriod, xExpectedNumber;
/*-----------------------------------------------------------*/
static void prvTest4_CheckAutoReloadTimersCanBeStopped( void )
{
{
uint8_t ucTimer;
/* Check the auto reload timers can be stopped correctly, and correctly
@ -749,7 +749,7 @@ static TickType_t uxTick = ( TickType_t ) -1;
if( uxTick == 0 )
{
/* The timers will have been created, but not started. Start them now
/* The timers will have been created, but not started. Start them now
by setting their period. */
ucISRAutoReloadTimerCounter = 0;
ucISROneShotTimerCounter = 0;
@ -765,7 +765,7 @@ static TickType_t uxTick = ( TickType_t ) -1;
/* First timer was started, try starting the second timer. */
if( xTimerChangePeriodFromISR( xISROneShotTimer, xBasePeriod, NULL ) == pdPASS )
{
/* Both timers were started, so set the uxTick back to its
/* Both timers were started, so set the uxTick back to its
proper value. */
uxTick = 0;
}
@ -805,7 +805,7 @@ static TickType_t uxTick = ( TickType_t ) -1;
{
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
}
}
else if( uxTick == ( ( 2 * xBasePeriod ) + xMargin ) )
{
@ -817,7 +817,7 @@ static TickType_t uxTick = ( TickType_t ) -1;
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
if( ucISROneShotTimerCounter != 1 )
{
xTestStatus = pdFAIL;
@ -834,13 +834,13 @@ static TickType_t uxTick = ( TickType_t ) -1;
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
if( ucISROneShotTimerCounter != 1 )
{
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
}
}
else if( uxTick == ( 3 * xBasePeriod ) )
{
/* Start the one shot timer again. */
@ -856,17 +856,17 @@ static TickType_t uxTick = ( TickType_t ) -1;
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
if( ucISROneShotTimerCounter != 1 )
{
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
/* Now stop the auto reload timer. The one shot timer was started
a few ticks ago. */
xTimerStopFromISR( xISRAutoReloadTimer, NULL );
}
}
else if( uxTick == ( 4 * ( xBasePeriod - xMargin ) ) )
{
/* The auto reload timer is now stopped, and the one shot timer is
@ -877,13 +877,13 @@ static TickType_t uxTick = ( TickType_t ) -1;
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
if( ucISROneShotTimerCounter != 1 )
{
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
}
}
else if( uxTick == ( ( 4 * xBasePeriod ) + xMargin ) )
{
/* The auto reload timer is now stopped, and the one shot timer is
@ -894,13 +894,13 @@ static TickType_t uxTick = ( TickType_t ) -1;
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
if( ucISROneShotTimerCounter != 2 )
{
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
}
}
else if( uxTick == ( 8 * xBasePeriod ) )
{
/* The auto reload timer is now stopped, and the one shot timer has
@ -911,16 +911,16 @@ static TickType_t uxTick = ( TickType_t ) -1;
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
if( ucISROneShotTimerCounter != 2 )
{
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
/* Now reset the one shot timer. */
xTimerResetFromISR( xISROneShotTimer, NULL );
}
}
else if( uxTick == ( ( 9 * xBasePeriod ) - xMargin ) )
{
/* Only the one shot timer should be running, but it should not have
@ -931,15 +931,15 @@ static TickType_t uxTick = ( TickType_t ) -1;
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
if( ucISROneShotTimerCounter != 2 )
{
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
xTimerResetFromISR( xISROneShotTimer, NULL );
}
}
else if( uxTick == ( ( 10 * xBasePeriod ) - ( 2 * xMargin ) ) )
{
/* Only the one shot timer should be running, but it should not have
@ -950,13 +950,13 @@ static TickType_t uxTick = ( TickType_t ) -1;
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
if( ucISROneShotTimerCounter != 2 )
{
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
xTimerResetFromISR( xISROneShotTimer, NULL );
}
else if( uxTick == ( ( 11 * xBasePeriod ) - ( 3 * xMargin ) ) )
@ -969,15 +969,15 @@ static TickType_t uxTick = ( TickType_t ) -1;
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
if( ucISROneShotTimerCounter != 2 )
{
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
xTimerResetFromISR( xISROneShotTimer, NULL );
}
}
else if( uxTick == ( ( 12 * xBasePeriod ) - ( 2 * xMargin ) ) )
{
/* Only the one shot timer should have been running and this time it
@ -990,7 +990,7 @@ static TickType_t uxTick = ( TickType_t ) -1;
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
if( ucISROneShotTimerCounter != 3 )
{
xTestStatus = pdFAIL;
@ -1007,15 +1007,15 @@ static TickType_t uxTick = ( TickType_t ) -1;
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
if( ucISROneShotTimerCounter != 3 )
{
xTestStatus = pdFAIL;
configASSERT( xTestStatus );
}
uxTick = ( TickType_t ) -1;
}
}
}
/*-----------------------------------------------------------*/

View File

@ -1,5 +1,5 @@
/*
FreeRTOS V8.0.1 - Copyright (C) 2014 Real Time Engineers Ltd.
FreeRTOS V8.0.1 - Copyright (C) 2014 Real Time Engineers Ltd.
All rights reserved
VISIT http://www.FreeRTOS.org TO ENSURE YOU ARE USING THE LATEST VERSION.
@ -64,15 +64,15 @@
*/
/*
* Creates eight tasks, each of which loops continuously performing a floating
* Creates eight tasks, each of which loops continuously performing a floating
* point calculation.
*
* All the tasks run at the idle priority and never block or yield. This causes
* all eight tasks to time slice with the idle task. Running at the idle
* priority means that these tasks will get pre-empted any time another task is
* ready to run or a time slice occurs. More often than not the pre-emption
* will occur mid calculation, creating a good test of the schedulers context
* switch mechanism - a calculation producing an unexpected result could be a
* all eight tasks to time slice with the idle task. Running at the idle
* priority means that these tasks will get pre-empted any time another task is
* ready to run or a time slice occurs. More often than not the pre-emption
* will occur mid calculation, creating a good test of the schedulers context
* switch mechanism - a calculation producing an unexpected result could be a
* symptom of a corruption in the context of a task.
*/
@ -375,7 +375,7 @@ BaseType_t xReturn = pdPASS, xTask;
usTaskCheck[ xTask ] = pdFALSE;
}
}
return xReturn;
}

View File

@ -121,7 +121,7 @@ be overridden by a definition in FreeRTOSConfig.h. */
/* Misc. */
#define recmuSHORT_DELAY ( 20 / portTICK_PERIOD_MS )
#define recmuNO_DELAY ( ( TickType_t ) 0 )
#define recmuFIVE_TICK_DELAY ( ( TickType_t ) 5 )
#define recmuEIGHT_TICK_DELAY ( ( TickType_t ) 8 )
/* The three tasks as described at the top of this file. */
static void prvRecursiveMutexControllingTask( void *pvParameters );
@ -195,7 +195,7 @@ UBaseType_t ux;
long enough to ensure the polling task will execute again before the
block time expires. If the block time does expire then the error
flag will be set here. */
if( xSemaphoreTakeRecursive( xMutex, recmuFIVE_TICK_DELAY ) != pdPASS )
if( xSemaphoreTakeRecursive( xMutex, recmuEIGHT_TICK_DELAY ) != pdPASS )
{
xErrorOccurred = pdTRUE;
}