Added CM3 MPU demo.

pull/4/head
Richard Barry 16 years ago
parent 4640196beb
commit 5f896f1640

@ -0,0 +1,110 @@
/*
FreeRTOS V5.4.2 - Copyright (C) 2009 Real Time Engineers Ltd.
This file is part of the FreeRTOS distribution.
FreeRTOS is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License (version 2) as published by the
Free Software Foundation and modified by the FreeRTOS exception.
**NOTE** The exception to the GPL is included to allow you to distribute a
combined work that includes FreeRTOS without being obliged to provide the
source code for proprietary components outside of the FreeRTOS kernel.
Alternative commercial license and support terms are also available upon
request. See the licensing section of http://www.FreeRTOS.org for full
license details.
FreeRTOS is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
more details.
You should have received a copy of the GNU General Public License along
with FreeRTOS; if not, write to the Free Software Foundation, Inc., 59
Temple Place, Suite 330, Boston, MA 02111-1307 USA.
***************************************************************************
* *
* Looking for a quick start? Then check out the FreeRTOS eBook! *
* See http://www.FreeRTOS.org/Documentation for details *
* *
***************************************************************************
1 tab == 4 spaces!
Please ensure to read the configuration and relevant port sections of the
online documentation.
http://www.FreeRTOS.org - Documentation, latest information, license and
contact details.
http://www.SafeRTOS.com - A version that is certified for use in safety
critical systems.
http://www.OpenRTOS.com - Commercial support, development, porting,
licensing and training services.
*/
#ifndef FREERTOS_CONFIG_H
#define FREERTOS_CONFIG_H
/*-----------------------------------------------------------
* Application specific definitions.
*
* These definitions should be adjusted for your particular hardware and
* application requirements.
*
* THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
* FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
*
* See http://www.freertos.org/a00110.html.
*----------------------------------------------------------*/
#define configUSE_PREEMPTION 1
#define configUSE_IDLE_HOOK 0
#define configUSE_TICK_HOOK 1
#define configCPU_CLOCK_HZ ( ( unsigned portLONG ) 50000000 )
#define configTICK_RATE_HZ ( ( portTickType ) 1000 )
#define configMINIMAL_STACK_SIZE ( ( unsigned portSHORT ) 100 )
#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 24000 ) )
#define configMAX_TASK_NAME_LEN ( 12 )
#define configUSE_TRACE_FACILITY 1
#define configUSE_16_BIT_TICKS 0
#define configIDLE_SHOULD_YIELD 0
#define configUSE_CO_ROUTINES 0
#define configUSE_MUTEXES 1
#define configCHECK_FOR_STACK_OVERFLOW 0
#define configUSE_RECURSIVE_MUTEXES 1
#define configQUEUE_REGISTRY_SIZE 10
#define configGENERATE_RUN_TIME_STATS 0
#define configUSE_MALLOC_FAILED_HOOK 1
#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 )
#define configMAX_CO_ROUTINE_PRIORITIES ( 2 )
/* Set the following definitions to 1 to include the API function, or zero
to exclude the API function. */
#define INCLUDE_vTaskPrioritySet 1
#define INCLUDE_uxTaskPriorityGet 1
#define INCLUDE_vTaskDelete 1
#define INCLUDE_vTaskCleanUpResources 0
#define INCLUDE_vTaskSuspend 1
#define INCLUDE_vTaskDelayUntil 1
#define INCLUDE_vTaskDelay 1
#define INCLUDE_uxTaskGetStackHighWaterMark 1
#ifdef __NVIC_PRIO_BITS
#define configPRIO_BITS __NVIC_PRIO_BITS
#else
#define configPRIO_BITS 3
#endif
#define configUNUSED_PRIO_BITS ( ( unsigned portCHAR ) ( 8 - configPRIO_BITS ) )
#define configKERNEL_INTERRUPT_PRIORITY ( ( unsigned portCHAR ) 7 << configUNUSED_PRIO_BITS ) /* Priority 7, or 255 as only the top three bits are implemented. This is the lowest priority. */
#define configMAX_SYSCALL_INTERRUPT_PRIORITY ( ( unsigned portCHAR ) 5 << configUNUSED_PRIO_BITS ) /* Priority 5, or 160 as only the top three bits are implemented. */
#define pvPortMallocAligned( x, puxStackBuffer ) ( ( puxStackBuffer == NULL ) ? ( pvPortMalloc( x ) ) : ( puxStackBuffer ) )
#define vPortFreeAligned( x ) ( void ) x
#endif /* FREERTOS_CONFIG_H */

@ -0,0 +1,196 @@
/*****************************************************************************
* Copyright (c) 2006 Rowley Associates Limited. *
* *
* This file may be distributed under the terms of the License Agreement *
* provided with this software. *
* *
* THIS FILE IS PROVIDED AS IS WITH NO WARRANTY OF ANY KIND, INCLUDING THE *
* WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. *
*****************************************************************************/
/*****************************************************************************
* Preprocessor Definitions
* ------------------------
*
* STARTUP_FROM_RESET
*
* If defined, the program will startup from power-on/reset. If not defined
* the program will just loop endlessly from power-on/reset.
*
* This definition is not defined by default on this target because the
* debugger is unable to reset this target and maintain control of it over the
* JTAG interface. The advantage of doing this is that it allows the debugger
* to reset the CPU and run programs from a known reset CPU state on each run.
* It also acts as a safety net if you accidently download a program in FLASH
* that crashes and prevents the debugger from taking control over JTAG
* rendering the target unusable over JTAG. The obvious disadvantage of doing
* this is that your application will not startup without the debugger.
*
* We advise that on this target you keep STARTUP_FROM_RESET undefined whilst
* you are developing and only define STARTUP_FROM_RESET when development is
* complete.
*
*****************************************************************************/
.extern xPortPendSVHandler
.extern xPortSysTickHandler
.extern vPortSVCHandler
.global reset_handler
.macro DEFAULT_ISR_HANDLER name=
.thumb_func
.weak \name
\name:
1: b 1b /* endless loop */
.endm
.section .vectors, "ax"
.code 16
.align 0
.global _vectors
_vectors:
.word __stack_end__
#ifdef STARTUP_FROM_RESET
.word reset_handler
#else
.word reset_wait
#endif /* STARTUP_FROM_RESET */
.word Nmi_ISR
.word Fault_ISR
.word MPU_Fault_ISR
.word 0 /* Populate if using Bus fault */
.word 0 /* Populate if using Usage fault */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word 0 /* Reserved */
.word vPortSVCHandler
.word 0 /* Populate if using a debug monitor */
.word 0 /* Reserved */
.word xPortPendSVHandler
.word xPortSysTickHandler
.word GPIO_Port_A_ISR
.word GPIO_Port_B_ISR
.word GPIO_Port_C_ISR
.word GPIO_Port_D_ISR
.word GPIO_Port_E_ISR
.word UART0_ISR
.word UART1_ISR
.word SSI_ISR
.word I2C_ISR
.word PWM_Fault_ISR
.word PWM_Generator_0_ISR
.word PWM_Generator_1_ISR
.word PWM_Generator_2_ISR
.word QEI_ISR
.word ADC_Sequence_0_ISR
.word ADC_Sequence_1_ISR
.word ADC_Sequence_2_ISR
.word ADC_Sequence_3_ISR
.word Watchdog_Timer_ISR
.word Timer0A_ISR
.word Timer0B_ISR
.word Timer1A_ISR
.word Timer1B_ISR
.word Timer2A_ISR
.word Timer2B_ISR
.word Analog_Comparator_0_ISR
.word Analog_Comparator_1_ISR
.word Analog_Comparator_2_ISR
.word System_Control_ISR
.word FLASH_Control_ISR
.word GPIO_Port_F_ISR
.word GPIO_Port_G_ISR
.word GPIO_Port_H_ISR
.word UART2_ISR
.word SSI1_ISR
.word Timer3A_ISR
.word Timer3B_ISR
.word I2C1_ISR
.word QEI1_ISR
.word CAN0_ISR
.word CAN1_ISR
.word CAN2_ISR
.word EMAC_ISR
.word HIBERNATE_ISR
.word USB0_ISR
.word PWM_Generator_3_ISR
.word uDMA_Software_Transfer_ISR
.word uDMA_Error_ISR
_vectors_end:
.section .init, "ax"
.thumb_func
reset_handler:
#ifdef __RAM_BUILD
/* If this is a RAM build, configure vector table offset register to point
to the RAM vector table. */
ldr r0, =0xE000ED08
ldr r1, =_vectors
str r1, [r0]
#endif
b _start
DEFAULT_ISR_HANDLER Nmi_ISR
/*DEFAULT_ISR_HANDLER Fault_ISR*/
/*DEFAULT_ISR_HANDLER MPU_Fault_ISR*/
DEFAULT_ISR_HANDLER SVCall_ISR
DEFAULT_ISR_HANDLER SysTick_ISR
DEFAULT_ISR_HANDLER PendSV_ISR
DEFAULT_ISR_HANDLER GPIO_Port_A_ISR
DEFAULT_ISR_HANDLER GPIO_Port_B_ISR
DEFAULT_ISR_HANDLER GPIO_Port_C_ISR
DEFAULT_ISR_HANDLER GPIO_Port_D_ISR
DEFAULT_ISR_HANDLER GPIO_Port_E_ISR
DEFAULT_ISR_HANDLER UART0_ISR
DEFAULT_ISR_HANDLER UART1_ISR
DEFAULT_ISR_HANDLER SSI_ISR
DEFAULT_ISR_HANDLER I2C_ISR
DEFAULT_ISR_HANDLER PWM_Fault_ISR
DEFAULT_ISR_HANDLER PWM_Generator_0_ISR
DEFAULT_ISR_HANDLER PWM_Generator_1_ISR
DEFAULT_ISR_HANDLER PWM_Generator_2_ISR
DEFAULT_ISR_HANDLER QEI_ISR
DEFAULT_ISR_HANDLER ADC_Sequence_0_ISR
DEFAULT_ISR_HANDLER ADC_Sequence_1_ISR
DEFAULT_ISR_HANDLER ADC_Sequence_2_ISR
DEFAULT_ISR_HANDLER ADC_Sequence_3_ISR
DEFAULT_ISR_HANDLER Watchdog_Timer_ISR
DEFAULT_ISR_HANDLER Timer0A_ISR
DEFAULT_ISR_HANDLER Timer0B_ISR
DEFAULT_ISR_HANDLER Timer1A_ISR
DEFAULT_ISR_HANDLER Timer1B_ISR
DEFAULT_ISR_HANDLER Timer2A_ISR
DEFAULT_ISR_HANDLER Timer2B_ISR
DEFAULT_ISR_HANDLER Analog_Comparator_0_ISR
DEFAULT_ISR_HANDLER Analog_Comparator_1_ISR
DEFAULT_ISR_HANDLER Analog_Comparator_2_ISR
DEFAULT_ISR_HANDLER System_Control_ISR
DEFAULT_ISR_HANDLER FLASH_Control_ISR
DEFAULT_ISR_HANDLER GPIO_Port_F_ISR
DEFAULT_ISR_HANDLER GPIO_Port_G_ISR
DEFAULT_ISR_HANDLER GPIO_Port_H_ISR
DEFAULT_ISR_HANDLER UART2_ISR
DEFAULT_ISR_HANDLER SSI1_ISR
DEFAULT_ISR_HANDLER Timer3A_ISR
DEFAULT_ISR_HANDLER Timer3B_ISR
DEFAULT_ISR_HANDLER I2C1_ISR
DEFAULT_ISR_HANDLER QEI1_ISR
DEFAULT_ISR_HANDLER CAN0_ISR
DEFAULT_ISR_HANDLER CAN1_ISR
DEFAULT_ISR_HANDLER CAN2_ISR
DEFAULT_ISR_HANDLER ETHERNET_ISR
DEFAULT_ISR_HANDLER HIBERNATE_ISR
DEFAULT_ISR_HANDLER USB0_ISR
DEFAULT_ISR_HANDLER PWM_Generator_3_ISR
DEFAULT_ISR_HANDLER uDMA_Software_Transfer_ISR
DEFAULT_ISR_HANDLER uDMA_Error_ISR
DEFAULT_ISR_HANDLER EMAC_ISR
#ifndef STARTUP_FROM_RESET
DEFAULT_ISR_HANDLER reset_wait
#endif /* STARTUP_FROM_RESET */

@ -0,0 +1,28 @@
/******************************************************************************
Target Script for LM3S.
Copyright (c) 2006 Rowley Associates Limited.
This file may be distributed under the terms of the License Agreement
provided with this software.
THIS FILE IS PROVIDED AS IS WITH NO WARRANTY OF ANY KIND, INCLUDING THE
WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
******************************************************************************/
function Reset()
{
TargetInterface.resetAndStop(1000);
}
function RAMReset()
{
Reset();
}
function FLASHReset()
{
Reset();
}

@ -0,0 +1,52 @@
<!DOCTYPE CrossStudio_Project_File>
<solution Name="RTOSDemo" version="2">
<project Name="RTOSDemo">
<configuration Name="Common" Target="LM3S8962" arm_architecture="v7M" arm_core_type="Cortex-M3" arm_linker_fiq_stack_size="0" arm_linker_heap_size="0" arm_linker_irq_stack_size="0" arm_linker_process_stack_size="0" arm_linker_stack_size="400" arm_simulator_memory_simulation_filename="$(PackagesDir)/targets/Luminary_LM3S/LM3SSimulatorMemory.dll" arm_simulator_memory_simulation_parameter="0x40000;0x10000" arm_target_debug_interface_type="ADIv5" arm_target_flash_loader_type="LIBMEM RPC Loader" build_remove_unused_symbols="No" c_only_additional_options="-Wall;-Wextra" c_preprocessor_definitions="sprintf=usprintf;snprintf=usnprintf;printf=uipprintf" c_user_include_directories="..\\..\\Source\\include;..\\..\\Source\\portable\\GCC\\ARM_CM3_MPU;..\\Common\\include;..\\Common\\drivers\\LuminaryMicro;.;$(SamplesDir)/Luminary_Stellaris_Driver_Library" gcc_optimization_level="None" linker_additional_files="" linker_memory_map_file="$(PackagesDir)/targets/Luminary_LM3S/LM3S8962_MemoryMap.xml" linker_output_format="None" linker_printf_fmt_level="int" linker_printf_width_precision_supported="No" linker_scanf_fmt_level="int" project_directory="" project_type="Executable" property_groups_file_path="$(PackagesDir)/targets/Luminary_LM3S/propertyGroups.xml"/>
<configuration Name="Flash" Placement="Flash" arm_target_flash_loader_file_path="$(PackagesDir)/targets/Luminary_LM3S/Release/Loader.elf" linker_section_placement_file="$(ProjectDir)/flash_placement.xml" target_reset_script="FLASHReset()"/>
<configuration Name="RAM" Placement="RAM" linker_section_placement_file="$(PackagesDir)/targets/Luminary_LM3S/ram_placement.xml" target_reset_script="RAMReset()"/>
<folder Name="Source Files">
<configuration Name="Common" filter="c;cpp;cxx;cc;h;s;asm;inc"/>
<folder Name="FreeRTOS MPU">
<folder Name="include" file_name="">
<file file_name="../../Source/portable/GCC/ARM_CM3/portmacro.h"/>
<file file_name="../../Source/include/task.h"/>
<file file_name="../../Source/include/FreeRTOS.h"/>
<file file_name="../../Source/include/list.h"/>
<file file_name="../../Source/include/portable.h"/>
<file file_name="../../Source/include/projdefs.h"/>
<file file_name="../../Source/include/queue.h"/>
<file file_name="../../Source/include/semphr.h"/>
<file file_name="../../Source/include/StackMacros.h"/>
<file file_name="../../Source/include/mpu_wrappers.h"/>
</folder>
<file file_name="../../Source/tasks.c"/>
<file file_name="../../Source/list.c"/>
<file file_name="../../Source/queue.c"/>
<file file_name="../../Source/portable/MemMang/heap_2.c"/>
<file file_name="../../Source/portable/GCC/ARM_CM3_MPU/port.c"/>
</folder>
<file file_name="main.c"/>
<folder Name="include">
<file file_name="FreeRTOSConfig.h"/>
</folder>
<folder Name="Libraries">
<file file_name="../Common/drivers/LuminaryMicro/Rowley/libdriver.a"/>
</folder>
<file file_name="../Common/drivers/LuminaryMicro/ustdlib.c"/>
</folder>
<folder Name="System Files">
<file file_name="thumb_crt0.s"/>
<file file_name="LM3S_Startup.s"/>
<file file_name="LM3S_Target.js">
<configuration Name="Common" build_exclude_from_build="Yes" file_type="Reset Script"/>
<configuration Name="THUMB Flash Debug" build_exclude_from_build="No"/>
</file>
</folder>
</project>
<configuration Name="THUMB Flash Debug" inherited_configurations="THUMB;Flash;Debug"/>
<configuration Name="THUMB" Platform="ARM" arm_instruction_set="THUMB" arm_library_instruction_set="THUMB" c_preprocessor_definitions="__THUMB" hidden="Yes"/>
<configuration Name="Flash" c_preprocessor_definitions="__FLASH_BUILD" hidden="Yes"/>
<configuration Name="Debug" build_debug_information="Yes" c_preprocessor_definitions="DEBUG" gcc_optimization_level="None" hidden="Yes" link_include_startup_code="No"/>
<configuration Name="THUMB Flash Release" inherited_configurations="THUMB;Flash;Release"/>
<configuration Name="Release" build_debug_information="No" c_additional_options="-g1" c_preprocessor_definitions="NDEBUG" gcc_optimization_level="Level 1" hidden="Yes" link_include_startup_code="No"/>
</solution>

@ -0,0 +1,56 @@
<!DOCTYPE CrossStudio_for_ARM_Session_File>
<session>
<Bookmarks/>
<Breakpoints/>
<ExecutionCountWindow/>
<Memory1>
<MemoryWindow autoEvaluate="0" addressText="0x200002d0" numColumns="8" sizeText="120" dataSize="1" radix="16" addressSpace="" />
</Memory1>
<Memory2>
<MemoryWindow autoEvaluate="0" addressText="" numColumns="8" sizeText="" dataSize="1" radix="16" addressSpace="" />
</Memory2>
<Memory3>
<MemoryWindow autoEvaluate="0" addressText="" numColumns="8" sizeText="" dataSize="1" radix="16" addressSpace="" />
</Memory3>
<Memory4>
<MemoryWindow autoEvaluate="0" addressText="" numColumns="8" sizeText="" dataSize="1" radix="16" addressSpace="" />
</Memory4>
<Project>
<ProjectSessionItem path="RTOSDemo" name="unnamed" />
<ProjectSessionItem path="RTOSDemo;RTOSDemo" name="unnamed" />
<ProjectSessionItem path="RTOSDemo;RTOSDemo;Source Files" name="unnamed" />
<ProjectSessionItem path="RTOSDemo;RTOSDemo;Source Files;FreeRTOS MPU" name="unnamed" />
</Project>
<Register1>
<RegisterWindow openNodes="CPU;CPU/xPSR;CPU/CFBP;CPU/CFBP/CONTROL[0];CPU/CFBP/CONTROL[1];Interrupt_Type" binaryNodes="" unsignedNodes="" visibleGroups="CPU;Interrupt_Type" decimalNodes="" octalNodes="" asciiNodes="" />
</Register1>
<Register2>
<RegisterWindow openNodes="MPU;MPU/MPU_Control;MPU/MPU_Region_Base_Address;MPU/MPU_Attribute_and_Size" binaryNodes="MPU/MPU_Attribute_and_Size/SIZE" unsignedNodes="" visibleGroups="MPU" decimalNodes="" octalNodes="" asciiNodes="" />
</Register2>
<Register3>
<RegisterWindow openNodes="System_Control_Block;System_Control_Block/System_Handlers_8_11_Priority;System_Control_Block/System_Handler_Control_and_State" binaryNodes="" unsignedNodes="" visibleGroups="System_Control_Block" decimalNodes="" octalNodes="" asciiNodes="" />
</Register3>
<Register4>
<RegisterWindow openNodes="" binaryNodes="" unsignedNodes="" visibleGroups="" decimalNodes="" octalNodes="" asciiNodes="" />
</Register4>
<TargetWindow programAction="" uploadFileType="" programLoadAddress="" programSize="" uploadFileName="" uploadMemoryInterface="" programFileName="" uploadStartAddress="" programFileType="" uploadSize="" programMemoryInterface="" />
<TraceWindow>
<Trace enabled="Yes" />
</TraceWindow>
<Watch1>
<Watches active="1" update="Never" />
</Watch1>
<Watch2>
<Watches active="0" update="Never" />
</Watch2>
<Watch3>
<Watches active="0" update="Never" />
</Watch3>
<Watch4>
<Watches active="0" update="Never" />
</Watch4>
<Files>
<SessionOpenFile useTextEdit="1" useBinaryEdit="0" codecName="Latin1" x="0" debugPath="C:\E\Dev\FreeRTOS\Trial\FreeRTOS_MPU\FreeRTOS\Demo\CORTEX_MPU_LM3Sxxxx_Rowley\main.c" y="701" path="C:\E\Dev\FreeRTOS\Trial\FreeRTOS_MPU\FreeRTOS\Demo\CORTEX_MPU_LM3Sxxxx_Rowley\main.c" left="0" selected="1" name="unnamed" top="682" />
</Files>
<ARMCrossStudioWindow activeProject="RTOSDemo" autoConnectTarget="Luminary USB Debug" debugSearchFileMap="" fileDialogInitialDirectory="C:\E\Dev\FreeRTOS\WorkingCopy\Source\portable\GCC\ARM_CM3_MPU" fileDialogDefaultFilter="*.*" autoConnectCapabilities="388991" debugSearchPath="" buildConfiguration="THUMB Flash Debug" />
</session>

@ -0,0 +1,24 @@
<!DOCTYPE Linker_Placement_File>
<Root name="FLASH Section Placement">
<MemorySegment name="FLASH">
<ProgramSection load="Yes" inputsections="*(.vectors .vectors.*)" name=".vectors"/>
<ProgramSection alignment="4" size="16K - 0x100" load="Yes" inputsections="*(privileged_functions)" name="privileged_functions"/>
<ProgramSection alignment="4" load="Yes" inputsections="*(.init .init.*)" name=".init"/>
<ProgramSection alignment="4" load="Yes" inputsections="*(.text .text.* .glue_7t .glue_7 .gnu.linkonce.t.* .gcc_except_table)" name=".text"/>
<ProgramSection alignment="4" load="Yes" inputsections="KEEP (*(SORT(.dtors.*))) KEEP (*(.dtors))" name=".dtors"/>
<ProgramSection alignment="4" load="Yes" inputsections="KEEP (*(SORT(.ctors.*))) KEEP (*(.ctors))" name=".ctors"/>
<ProgramSection alignment="4" load="Yes" inputsections="*(.rodata .rodata.* .gnu.linkonce.r.*)" name=".rodata"/>
<ProgramSection alignment="4" load="Yes" runin=".data_run" inputsections="*(.data .data.* .gnu.linkonce.d.*)" name=".data"/>
<ProgramSection alignment="4" load="Yes" runin=".fast_run" inputsections="*(.fast .fast.*)" name=".fast"/>
</MemorySegment>
<MemorySegment name="SRAM">
<ProgramSection alignment="4" size="256" alignment="256" load="No" inputsections="*(privileged_data)" name="privileged_data"/>
<ProgramSection name=".vectors_ram" size="" alignment="0x100" load="No"/>
<ProgramSection alignment="4" load="No" name=".data_run"/>
<ProgramSection alignment="4" load="No" inputsections="*(.bss .bss.* .gnu.linkonce.b.*) *(COMMON)" name=".bss"/>
<ProgramSection alignment="4" load="No" inputsections="*(.non_init .non_init.*)" name=".non_init"/>
<ProgramSection alignment="4" size="__HEAPSIZE__" load="No" name=".heap"/>
<ProgramSection alignment="4" size="__STACKSIZE__" load="No" name=".stack"/>
<ProgramSection alignment="4" load="No" name=".fast_run"/>
</MemorySegment>
</Root>

@ -0,0 +1,742 @@
/*
FreeRTOS V5.4.2 - Copyright (C) 2009 Real Time Engineers Ltd.
This file is part of the FreeRTOS distribution.
FreeRTOS is free software; you can redistribute it and/or modify it under
the terms of the GNU General Public License (version 2) as published by the
Free Software Foundation and modified by the FreeRTOS exception.
**NOTE** The exception to the GPL is included to allow you to distribute a
combined work that includes FreeRTOS without being obliged to provide the
source code for proprietary components outside of the FreeRTOS kernel.
Alternative commercial license and support terms are also available upon
request. See the licensing section of http://www.FreeRTOS.org for full
license details.
FreeRTOS is distributed in the hope that it will be useful, but WITHOUT
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
more details.
You should have received a copy of the GNU General Public License along
with FreeRTOS; if not, write to the Free Software Foundation, Inc., 59
Temple Place, Suite 330, Boston, MA 02111-1307 USA.
***************************************************************************
* *
* Looking for a quick start? Then check out the FreeRTOS eBook! *
* See http://www.FreeRTOS.org/Documentation for details *
* *
***************************************************************************
1 tab == 4 spaces!
Please ensure to read the configuration and relevant port sections of the
online documentation.
http://www.FreeRTOS.org - Documentation, latest information, license and
contact details.
http://www.SafeRTOS.com - A version that is certified for use in safety
critical systems.
http://www.OpenRTOS.com - Commercial support, development, porting,
licensing and training services.
*/
/* Standard includes. */
#include <string.h>
#include <__cross_studio_io.h>
/* Scheduler includes. */
#include "FreeRTOS.h"
#include "task.h"
#include "queue.h"
#include "semphr.h"
/* Hardware library includes. */
#include "hw_types.h"
#include "hw_sysctl.h"
#include "sysctl.h"
/*
* This file demonstrates the use of MPU using just three tasks - two 'reg test'
* tasks and one 'check' task. Read the comments above the
* function prototypes for more information.
*/
/*-----------------------------------------------------------*/
/* Misc constants. */
#define mainDONT_BLOCK ( 0 )
/* Definitions for the messages that can be sent to the check task. */
#define mainREG_TEST_1_STILL_EXECUTING ( 0 )
#define mainREG_TEST_2_STILL_EXECUTING ( 1 )
#define mainPRINT_SYSTEM_STATUS ( 2 )
/* GCC specifics. */
#define mainALIGN_TO( x ) __attribute__((aligned(x)))
/*-----------------------------------------------------------*/
/* Prototypes for functions that implement tasks. -----------*/
/*-----------------------------------------------------------*/
/*
* Prototype for the reg test tasks. Amongst other things, these fill the CPU
* registers with known values before checking that the registers still contain
* the expected values. Each of the two tasks use different values so an error
* in the context switch mechanism can be caught. Both reg test tasks execute
* at the idle priority so will get preempted regularly.
*/
static void prvRegTest1Task( void *pvParameters );
static void prvRegTest2Task( void *pvParameters );
/*
* Prototype for the check task. The check task demonstrates various features
* of the MPU before entering a loop where it waits for commands to arrive on a
* queue.
*
* The check task will periodically be commanded to print out a status message.
* If both the reg tests tasks are executing as expected the check task will
* print "PASS" to the debug port, otherwise it will print 'FAIL'. Debug port
* messages can be viewed within the CrossWorks IDE.
*/
static void prvCheckTask( void *pvParameters );
/*-----------------------------------------------------------*/
/* Prototypes for other misc functions. --------------------*/
/*-----------------------------------------------------------*/
/*
* Just configures any clocks and IO necessary.
*/
static void prvSetupHardware( void );
/*
* Simply deletes the calling task. The function is provided only because it
* is simpler to call from asm code than the normal vTaskDelete() API function.
* It has the noinline attribute because it is called from asm code.
*/
static void prvDeleteMe( void ) __attribute__((noinline));
/*
* Used by both reg test tasks to send messages to the check task. The message
* just lets the check task know that the sending is still functioning correctly.
* If a reg test task detects an error it will delete itself, and in so doing
* prevent itself from sending any more 'I'm Alive' messages to the check task.
*/
static void prvSendImAlive( xQueueHandle xHandle, unsigned long ulTaskNumber );
/*
* The check task is created with access to three memory regions (plus its
* stack). Each memory region is configured with different parameters and
* prvTestMemoryRegions() demonstrates what can and cannot be accessed for each
* region. prvTestMemoryRegions() also demonstrates a task that was created
* as a privileged task settings its own privilege level down to that of a user
* task.
*/
static void prvTestMemoryRegions( void );
/*-----------------------------------------------------------*/
/* The handle of the queue used to communicate between tasks and between tasks
and interrupts. Note that this is a file scope variable that falls outside of
any MPU region. As such other techniques have to be used to allow the tasks
to gain access to the queue. See the comments in the tasks themselves for
further information. */
static xQueueHandle xFileScopeCheckQueue = NULL;
/*-----------------------------------------------------------*/
/* Data used by the 'check' task. ---------------------------*/
/*-----------------------------------------------------------*/
/* Define the constants used to allocate the check task stack. Note that the
stack size is defined in words, not bytes. */
#define mainCHECK_TASK_STACK_SIZE_WORDS 128
#define mainCHECK_TASK_STACK_ALIGNMENT ( mainCHECK_TASK_STACK_SIZE_WORDS * sizeof( portSTACK_TYPE ) )
/* Declare the stack that will be used by the check task. The kernel will
automatically create an MPU region for the stack. The stack alignment must
match its size, so if 128 words are reserved for the stack then it must be
aligned to ( 128 * 4 ) bytes. */
static portSTACK_TYPE xCheckTaskStack[ mainCHECK_TASK_STACK_SIZE_WORDS ] mainALIGN_TO( mainCHECK_TASK_STACK_ALIGNMENT );
/* Declare three arrays - an MPU region will be created for each array
using the xTaskParameters structure below. Note that the arrays allocate
slightly more RAM than is actually assigned to the MPU region. This is to
permit writes off the end of the array to be detected even when the arrays are
placed in adjacent memory locations (with no gaps between them). The align
size must be a power of two. */
#define mainREAD_WRITE_ARRAY_SIZE 130
#define mainREAD_WRITE_ALIGN_SIZE 128
char cReadWriteArray[ mainREAD_WRITE_ARRAY_SIZE ] mainALIGN_TO( mainREAD_WRITE_ALIGN_SIZE );
#define mainREAD_ONLY_ARRAY_SIZE 260
#define mainREAD_ONLY_ALIGN_SIZE 256
char cReadOnlyArray[ mainREAD_ONLY_ARRAY_SIZE ] mainALIGN_TO( mainREAD_ONLY_ALIGN_SIZE );
#define mainPRIVILEGED_ONLY_ACCESS_ARRAY_SIZE 130
#define mainPRIVILEGED_ONLY_ACCESS_ALIGN_SIZE 128
char cPrivilegedOnlyAccessArray[ mainPRIVILEGED_ONLY_ACCESS_ALIGN_SIZE ] mainALIGN_TO( mainPRIVILEGED_ONLY_ACCESS_ALIGN_SIZE );
/* Fill in a xTaskParameters structure to define the check task. */
static const xTaskParameters xCheckTaskParameters =
{
prvCheckTask, /* pvTaskCode - the function that implements the task. */
( signed char * ) "Check", /* pcName */
mainCHECK_TASK_STACK_SIZE_WORDS, /* usStackDepth - defined in words, not bytes. */
( void * ) 0x12121212, /* pvParameters - this value is just to test that the parameter is being passed into the task correctly. */
( tskIDLE_PRIORITY + 1 ) | portPRIVILEGE_BIT,/* uxPriority - this is the highest priority task in the system. The task is created in privileged mode to demonstrate accessing the privileged only data. */
xCheckTaskStack, /* puxStackBuffer - the array to use as the task stack, as declared above. */
/* xRegions - In this case the xRegions array is used to create MPU regions
for all three of the arrays declared directly above. Each MPU region is
created with different parameters. */
{
/* Base address Length Parameters */
{ cReadWriteArray, mainREAD_WRITE_ALIGN_SIZE, portMPU_REGION_READ_WRITE },
{ cReadOnlyArray, mainREAD_ONLY_ALIGN_SIZE, portMPU_REGION_READ_ONLY },
{ cPrivilegedOnlyAccessArray, mainPRIVILEGED_ONLY_ACCESS_ALIGN_SIZE, portMPU_REGION_PRIVILEGED_READ_WRITE }
}
};
/* Three MPU regions are defined for use by the 'check' task when the task is
created. These are only used to demonstrate the MPU features and are not
actually necessary for the check task to fulfill its primary purpose. Instead
the MPU regions are replaced with those defined by xAltRegions prior to the
check task receiving any data on the queue or printing any messages to the
debug console. The region configured by xAltRegions just gives the check task
access to the debug variables that form part of the Rowley library, and are
accessed within the debug_printf() function. */
extern unsigned long dbgCntrlWord_mempoll;
static const xMemoryRegion xAltRegions[ portNUM_CONFIGURABLE_REGIONS ] =
{
/* Base address Length Parameters */
{ ( void * ) &dbgCntrlWord_mempoll, 32, portMPU_REGION_READ_WRITE },
{ 0, 0, 0 },
{ 0, 0, 0 }
};
/*-----------------------------------------------------------*/
/* Data used by the 'reg test' tasks. -----------------------*/
/*-----------------------------------------------------------*/
/* Define the constants used to allocate the reg test task stacks. Note that
that stack size is defined in words, not bytes. */
#define mainREG_TEST_STACK_SIZE_WORDS 128
#define mainREG_TEST_STACK_ALIGNMENT ( mainREG_TEST_STACK_SIZE_WORDS * sizeof( portSTACK_TYPE ) )
/* Declare the stacks that will be used by the reg test tasks. The kernel will
automatically create an MPU region for the stack. The stack alignment must
match its size, so if 128 words are reserved for the stack then it must be
aligned to ( 128 * 4 ) bytes. */
static portSTACK_TYPE xRegTest1Stack[ mainREG_TEST_STACK_SIZE_WORDS ] mainALIGN_TO( mainREG_TEST_STACK_ALIGNMENT );
static portSTACK_TYPE xRegTest2Stack[ mainREG_TEST_STACK_SIZE_WORDS ] mainALIGN_TO( mainREG_TEST_STACK_ALIGNMENT );
/* Fill in a xTaskParameters structure per reg test task to define the tasks. */
static const xTaskParameters xRegTest1Parameters =
{
prvRegTest1Task, /* pvTaskCode - the function that implements the task. */
( signed char * ) "RegTest1", /* pcName */
mainREG_TEST_STACK_SIZE_WORDS, /* usStackDepth */
( void * ) 0x12345678, /* pvParameters - this value is just to test that the parameter is being passed into the task correctly. */
tskIDLE_PRIORITY | portPRIVILEGE_BIT, /* uxPriority - note that this task is created with privileges to demonstrate one method of passing a queue handle into the task. */
xRegTest1Stack, /* puxStackBuffer - the array to use as the task stack, as declared above. */
{ /* xRegions - this task does not use any non-stack data. */
/* Base address Length Parameters */
{ 0x00, 0x00, 0x00 },
{ 0x00, 0x00, 0x00 },
{ 0x00, 0x00, 0x00 }
}
};
/*-----------------------------------------------------------*/
static xTaskParameters xRegTest2Parameters =
{
prvRegTest2Task, /* pvTaskCode - the function that implements the task. */
( signed char * ) "RegTest2", /* pcName */
mainREG_TEST_STACK_SIZE_WORDS, /* usStackDepth */
( void * ) NULL, /* pvParameters - this task uses the parameter to pass in a queue handle, but the queue is not created yet. */
tskIDLE_PRIORITY, /* uxPriority */
xRegTest2Stack, /* puxStackBuffer - the array to use as the task stack, as declared above. */
{ /* xRegions - this task does not use any non-stack data. */
/* Base address Length Parameters */
{ 0x00, 0x00, 0x00 },
{ 0x00, 0x00, 0x00 },
{ 0x00, 0x00, 0x00 }
}
};
/*-----------------------------------------------------------*/
int main( void )
{
prvSetupHardware();
/* Create the queue used to pass "I'm alive" messages to the check task. */
xFileScopeCheckQueue = xQueueCreate( 1, sizeof( unsigned long ) );
/* One check task uses the task parameter to receive the queue handle.
This allows the file scope variable to be accessed from within the task.
The pvParameters member of xRegTest2Parameters can only be set after the
queue has been created. */
xRegTest2Parameters.pvParameters = xFileScopeCheckQueue;
/* Create the three test tasks. Handles to the created tasks are not
required, hence the second parameter is NULL. */
xTaskCreateRestricted( &xRegTest1Parameters, NULL );
xTaskCreateRestricted( &xRegTest2Parameters, NULL );
xTaskCreateRestricted( &xCheckTaskParameters, NULL );
/* Start the scheduler. */
vTaskStartScheduler();
/* Will only get here if there was insufficient memory to create the idle
task. */
for( ;; );
return 0;
}
/*-----------------------------------------------------------*/
static void prvCheckTask( void *pvParameters )
{
/* This task is created in privileged mode so can access the file scope
queue variable. Take a stack copy of this before the task is set into user
mode. Once that task is in user mode the file scope queue variable will no
longer be accessible but the stack copy will. */
xQueueHandle xQueue = xFileScopeCheckQueue;
long lMessage;
unsigned long ulStillAliveCounts[ 2 ] = { 0 };
const char *pcStatusMessage = "PASS\r\n";
/* Just to remove compiler warning. */
( void ) pvParameters;
/* Demonstrate how the various memory regions can and can't be accessed.
The task privilege is set down to user mode within this function. */
prvTestMemoryRegions();
/* Change the memory regions allocated to this task to those initially
set up for demonstration purposes to those actually required by the task. */
vTaskAllocateMPURegions( NULL, xAltRegions );
/* This loop performs the main function of the task, which is blocking
on a message queue then processing each message as it arrives. */
for( ;; )
{
/* Wait for the next message to arrive. */
xQueueReceive( xQueue, &lMessage, portMAX_DELAY );
switch( lMessage )
{
case mainREG_TEST_1_STILL_EXECUTING :
/* Message from task 1, so task 1 must still be executing. */
( ulStillAliveCounts[ 0 ] )++;
break;
case mainREG_TEST_2_STILL_EXECUTING :
/* Message from task 2, so task 2 must still be executing. */
( ulStillAliveCounts[ 1 ] )++;
break;
case mainPRINT_SYSTEM_STATUS :
/* Message from tick hook, time to print out the system
status. If messages has stopped arriving from either reg
test task then the status must be set to fail. */
if( ( ulStillAliveCounts[ 0 ] == 0 ) || ( ulStillAliveCounts[ 1 ] == 0 ) )
{
/* One or both of the test tasks are no longer sending
'still alive' messages. */
pcStatusMessage = "FAIL\r\n";
}
/* Print a pass/fail message to the terminal. This will be
visible in the CrossWorks IDE. */
debug_printf( pcStatusMessage );
/* Reset the count of 'still alive' messages. */
memset( ulStillAliveCounts, 0x00, sizeof( ulStillAliveCounts ) );
break;
default :
/* Something unexpected happened. Delete this task so the
error is apparent (no output will be displayed). */
prvDeleteMe();
break;
}
}
}
/*-----------------------------------------------------------*/
static void prvTestMemoryRegions( void )
{
long l;
char cTemp;
/* The check task is created in the privileged mode. The privileged array
can be both read from and written to while this task is privileged. */
cPrivilegedOnlyAccessArray[ 0 ] = 'a';
if( cPrivilegedOnlyAccessArray[ 0 ] != 'a' )
{
/* Something unexpected happened. Delete this task so the error is
apparent (no output will be displayed). */
prvDeleteMe();
}
/* Writing off the end of the RAM allocated to this task will *NOT* cause a
protection fault because the task is still executing in a privileged mode.
Uncomment the following to test. */
/*cPrivilegedOnlyAccessArray[ mainPRIVILEGED_ONLY_ACCESS_ALIGN_SIZE ] = 'a';*/
/* Now set the task into user mode. */
portSWITCH_TO_USER_MODE();
/* Accessing the privileged only array will now cause a fault. Uncomment
the following line to test. */
/*cPrivilegedOnlyAccessArray[ 0 ] = 'a';*/
/* The read/write array can still be successfully read and written. */
for( l = 0; l < mainREAD_WRITE_ALIGN_SIZE; l++ )
{
cReadWriteArray[ l ] = 'a';
if( cReadWriteArray[ l ] != 'a' )
{
/* Something unexpected happened. Delete this task so the error is
apparent (no output will be displayed). */
prvDeleteMe();
}
}
/* But attempting to read or write off the end of the RAM allocated to this
task will cause a fault. Uncomment either of the following two lines to
test. */
/* cReadWriteArray[ 0 ] = cReadWriteArray[ -1 ]; */
/* cReadWriteArray[ mainREAD_WRITE_ALIGN_SIZE ] = 0x00; */
/* The read only array can be successfully read... */
for( l = 0; l < mainREAD_ONLY_ALIGN_SIZE; l++ )
{
cTemp = cReadOnlyArray[ l ];
}
/* ...but cannot be written. Uncomment the following line to test. */
/* cReadOnlyArray[ 0 ] = 'a'; */
/* Writing to the first and last locations in the stack array should not
cause a protection fault. Note that doing this will cause the kernel to
detect a stack overflow if configCHECK_FOR_STACK_OVERFLOW is greater than
1. */
xCheckTaskStack[ 0 ] = 0;
xCheckTaskStack[ mainCHECK_TASK_STACK_SIZE_WORDS - 1 ] = 0;
/* Writing off either end of the stack array should cause a protection
fault, uncomment either of the following two lines to test. */
/* xCheckTaskStack[ -1 ] = 0; */
/* xCheckTaskStack[ mainCHECK_TASK_STACK_SIZE_WORDS ] = 0; */
}
/*-----------------------------------------------------------*/
static void prvRegTest1Task( void *pvParameters )
{
/* This task is created in privileged mode so can access the file scope
queue variable. Take a stack copy of this before the task is set into user
mode. Once that task is in user mode the file scope queue variable will no
longer be accessible but the stack copy will. */
xQueueHandle xQueue = xFileScopeCheckQueue;
/* Now the queue handle has been obtained the task can switch to user
mode. This is just one method of passing a handle into a protected
task, the other reg test task uses the task parameter instead. */
portSWITCH_TO_USER_MODE();
/* First check that the parameter value is as expected. */
if( pvParameters != ( void * ) 0x12345678 )
{
/* Error detected. Delete the task so it stops communicating with
the check task. */
prvDeleteMe();
}
for( ;; )
{
/* This task tests the kernel context switch mechanism by reading and
writing directly to registers - which requires the test to be written
in assembly code. */
__asm volatile
(
" MOV R4, #104 \n" /* Set registers to a known value. R0 to R1 are done in the loop below. */
" MOV R5, #105 \n"
" MOV R6, #106 \n"
" MOV R8, #108 \n"
" MOV R9, #109 \n"
" MOV R10, #110 \n"
" MOV R11, #111 \n"
"reg1loop: \n"
" MOV R0, #100 \n" /* Set the scratch registers to known values - done inside the loop as they get clobbered. */
" MOV R1, #101 \n"
" MOV R2, #102 \n"
" MOV R3, #103 \n"
" MOV R12, #112 \n"
" SVC #1 \n" /* Yield just to increase test coverage. */
" CMP R0, #100 \n" /* Check all the registers still contain their expected values. */
" BNE prvDeleteMe \n" /* Value was not as expected, delete the task so it stops communicating with the check task. */
" CMP R1, #101 \n"
" BNE prvDeleteMe \n"
" CMP R2, #102 \n"
" BNE prvDeleteMe \n"
" CMP R3, #103 \n"
" BNE prvDeleteMe \n"
" CMP R4, #104 \n"
" BNE prvDeleteMe \n"
" CMP R5, #105 \n"
" BNE prvDeleteMe \n"
" CMP R6, #106 \n"
" BNE prvDeleteMe \n"
" CMP R8, #108 \n"
" BNE prvDeleteMe \n"
" CMP R9, #109 \n"
" BNE prvDeleteMe \n"
" CMP R10, #110 \n"
" BNE prvDeleteMe \n"
" CMP R11, #111 \n"
" BNE prvDeleteMe \n"
" CMP R12, #112 \n"
" BNE prvDeleteMe \n"
);
/* Send mainREG_TEST_1_STILL_EXECUTING to the check task to indicate that this
task is still functioning. */
prvSendImAlive( xQueue, mainREG_TEST_1_STILL_EXECUTING );
/* Go back to check all the register values again. */
__asm volatile( " B reg1loop " );
}
}
/*-----------------------------------------------------------*/
static void prvRegTest2Task( void *pvParameters )
{
/* The queue handle is passed in as the task parameter. This is one method of
passing data into a protected task, the other check task uses a different
method. */
xQueueHandle xQueue = ( xQueueHandle ) pvParameters;
for( ;; )
{
/* This task tests the kernel context switch mechanism by reading and
writing directly to registers - which requires the test to be written
in assembly code. */
__asm volatile
(
" MOV R4, #4 \n" /* Set registers to a known value. R0 to R1 are done in the loop below. */
" MOV R5, #5 \n"
" MOV R6, #6 \n"
" MOV R8, #8 \n" /* Frame pointer is omitted as it must not be changed. */
" MOV R9, #9 \n"
" MOV R10, 10 \n"
" MOV R11, #11 \n"
"reg2loop: \n"
" MOV R0, #13 \n" /* Set the scratch registers to known values - done inside the loop as they get clobbered. */
" MOV R1, #1 \n"
" MOV R2, #2 \n"
" MOV R3, #3 \n"
" MOV R12, #12 \n"
" CMP R0, #13 \n" /* Check all the registers still contain their expected values. */
" BNE prvDeleteMe \n" /* Value was not as expected, delete the task so it stops communicating with the check task */
" CMP R1, #1 \n"
" BNE prvDeleteMe \n"
" CMP R2, #2 \n"
" BNE prvDeleteMe \n"
" CMP R3, #3 \n"
" BNE prvDeleteMe \n"
" CMP R4, #4 \n"
" BNE prvDeleteMe \n"
" CMP R5, #5 \n"
" BNE prvDeleteMe \n"
" CMP R6, #6 \n"
" BNE prvDeleteMe \n"
" CMP R8, #8 \n"
" BNE prvDeleteMe \n"
" CMP R9, #9 \n"
" BNE prvDeleteMe \n"
" CMP R10, #10 \n"
" BNE prvDeleteMe \n"
" CMP R11, #11 \n"
" BNE prvDeleteMe \n"
" CMP R12, #12 \n"
" BNE prvDeleteMe \n"
);
/* Send mainREG_TEST_2_STILL_EXECUTING to the check task to indicate that this
task is still functioning. */
prvSendImAlive( xQueue, mainREG_TEST_2_STILL_EXECUTING );
/* Go back to check all the register values again. */
__asm volatile( " B reg2loop " );
}
}
/*-----------------------------------------------------------*/
static void prvDeleteMe( void )
{
vTaskDelete( NULL );
}
/*-----------------------------------------------------------*/
static void prvSendImAlive( xQueueHandle xHandle, unsigned long ulTaskNumber )
{
if( xHandle != NULL )
{
xQueueSend( xHandle, &ulTaskNumber, mainDONT_BLOCK );
}
}
/*-----------------------------------------------------------*/
static void prvSetupHardware( void )
{
/* If running on Rev A2 silicon, turn the LDO voltage up to 2.75V. This is
a workaround to allow the PLL to operate reliably. */
if( DEVICE_IS_REVA2 )
{
SysCtlLDOSet( SYSCTL_LDO_2_75V );
}
/* Set the clocking to run from the PLL at 50 MHz */
SysCtlClockSet( SYSCTL_SYSDIV_4 | SYSCTL_USE_PLL | SYSCTL_OSC_MAIN | SYSCTL_XTAL_8MHZ );
}
/*-----------------------------------------------------------*/
void vApplicationTickHook( void )
{
static unsigned long ulCallCount;
const unsigned long ulCallsBetweenSends = 5000 / portTICK_RATE_MS;
const unsigned long ulMessage = mainPRINT_SYSTEM_STATUS;
portBASE_TYPE xDummy;
/* If configUSE_TICK_HOOK is set to 1 then this function will get called
from each RTOS tick. It is called from the tick interrupt and therefore
will be executing in the privileged state. */
ulCallCount++;
/* Is it time to print out the pass/fail message again? */
if( ulCallCount >= ulCallsBetweenSends )
{
ulCallCount = 0;
/* Send a message to the check task to command it to check that all
the tasks are still running then print out the status.
This is running in an ISR so has to use the "FromISR" version of
xQueueSend(). Because it is in an ISR it is running with privileges
so can access xFileScopeCheckQueue directly. */
xQueueSendFromISR( xFileScopeCheckQueue, &ulMessage, &xDummy );
}
}
/*-----------------------------------------------------------*/
void vApplicationStackOverflowHook( xTaskHandle *pxTask, signed portCHAR *pcTaskName )
{
/* If configCHECK_FOR_STACK_OVERFLOW is set to either 1 or 2 then this
function will automatically get called if a task overflows its stack. */
( void ) pxTask;
( void ) pcTaskName;
for( ;; );
}
/*-----------------------------------------------------------*/
void vApplicationMallocFailedHook( void )
{
/* If configUSE_MALLOC_FAILED_HOOK is set to 1 then this function will
be called automatically if a call to pvPortMalloc() fails. pvPortMalloc()
is called automatically when a task, queue or semaphore is created. */
for( ;; );
}
/*-----------------------------------------------------------*/
/* Just to keep the linker happy. */
void __error__( char *pcFilename, unsigned long ulLine )
{
( void ) pcFilename;
( void ) ulLine;
for( ;; );
}
/*-----------------------------------------------------------*/
/* Just to keep the linker happy. */
int uipprintf( const char *fmt, ... )
{
( void ) fmt;
return( 0 );
}
/*-----------------------------------------------------------*/
void hard_fault_handler(unsigned int * hardfault_args)
{
unsigned int stacked_r0;
unsigned int stacked_r1;
unsigned int stacked_r2;
unsigned int stacked_r3;
unsigned int stacked_r12;
unsigned int stacked_lr;
unsigned int stacked_pc;
unsigned int stacked_psr;
stacked_r0 = ((unsigned long) hardfault_args[0]);
stacked_r1 = ((unsigned long) hardfault_args[1]);
stacked_r2 = ((unsigned long) hardfault_args[2]);
stacked_r3 = ((unsigned long) hardfault_args[3]);
stacked_r12 = ((unsigned long) hardfault_args[4]);
stacked_lr = ((unsigned long) hardfault_args[5]);
stacked_pc = ((unsigned long) hardfault_args[6]);
stacked_psr = ((unsigned long) hardfault_args[7]);
/* Inspect stacked_pc to locate the offending instruction. */
for( ;; );
}
/*-----------------------------------------------------------*/
void Fault_ISR( void ) __attribute__((naked));
void Fault_ISR( void )
{
__asm volatile
(
" tst lr, #4 \n"
" ite eq \n"
" mrseq r0, msp \n"
" mrsne r0, psp \n"
" ldr r1, [r0, #24] \n"
" ldr r2, handler_address_const \n"
" bx r2 \n"
" handler_address_const: .word hard_fault_handler \n"
);
}
/*-----------------------------------------------------------*/
void MPU_Fault_ISR( void ) __attribute__((naked));
void MPU_Fault_ISR( void )
{
__asm volatile
(
" tst lr, #4 \n"
" ite eq \n"
" mrseq r0, msp \n"
" mrsne r0, psp \n"
" ldr r1, [r0, #24] \n"
" ldr r2, handler_address_const \n"
" bx r2 \n"
" handler2_address_const: .word hard_fault_handler \n"
);
}
/*-----------------------------------------------------------*/

@ -0,0 +1,233 @@
/*****************************************************************************
* Copyright (c) 2009 Rowley Associates Limited. *
* *
* This file may be distributed under the terms of the License Agreement *
* provided with this software. *
* *
* THIS FILE IS PROVIDED AS IS WITH NO WARRANTY OF ANY KIND, INCLUDING THE *
* WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. *
*****************************************************************************/
/*****************************************************************************
* Preprocessor Definitions
* ------------------------
* APP_ENTRY_POINT
*
* Defines the application entry point function, if undefined this setting
* defaults to "main".
*
* USE_PROCESS_STACK
*
* If defined, thread mode will be configured to use the process stack if
* the size of the process stack is greater than zero bytes in length.
*
* INITIALIZE_STACK
*
* If defined, the contents of the stack will be initialized to a the
* value 0xCC.
*
* FULL_LIBRARY
*
* If defined then
* - argc, argv are setup by the debug_getargs.
* - the exit symbol is defined and executes on return from main.
* - the exit symbol calls destructors, atexit functions and then debug_exit.
*
* If not defined then
* - argc and argv are zero.
* - no exit symbol, code loops on return from main.
*****************************************************************************/
#ifndef APP_ENTRY_POINT
#define APP_ENTRY_POINT main
#endif
#ifndef ARGSSPACE
#define ARGSSPACE 128
#endif
.global _start
.syntax unified
.extern APP_ENTRY_POINT
#ifdef FULL_LIBRARY
.global exit
#endif
.section .init, "ax"
.code 16
.align 2
.thumb_func
_start:
#ifdef __RAM_BUILD
ldr r1, =__stack_end__
mov sp, r1
#endif
#ifdef INITIALIZE_STACK
mov r2, #0xCC
ldr r0, =__stack_start__
#ifndef __RAM_BUILD
mov r1, sp
#endif
bl memory_set
#endif
#ifdef USE_PROCESS_STACK
/* Set up process stack if size > 0 */
ldr r1, =__stack_process_end__
ldr r0, =__stack_process_start__
subs r2, r1, r0
beq 1f
msr psp, r1
mov r2, #2
msr control, r2
#ifdef INITIALIZE_STACK
mov r2, #0xCC
bl memory_set
#endif
1:
#endif
/* Copy initialised memory sections into RAM (if necessary). */
ldr r0, =__data_load_start__
ldr r1, =__data_start__
ldr r2, =__data_end__
bl memory_copy
ldr r0, =__text_load_start__
ldr r1, =__text_start__
ldr r2, =__text_end__
bl memory_copy
ldr r0, =__fast_load_start__
ldr r1, =__fast_start__
ldr r2, =__fast_end__
bl memory_copy
ldr r0, =__ctors_load_start__
ldr r1, =__ctors_start__
ldr r2, =__ctors_end__
bl memory_copy
ldr r0, =__dtors_load_start__
ldr r1, =__dtors_start__
ldr r2, =__dtors_end__
bl memory_copy
ldr r0, =__rodata_load_start__
ldr r1, =__rodata_start__
ldr r2, =__rodata_end__
bl memory_copy
/* Zero the bss. */
ldr r0, =__bss_start__
ldr r1, =__bss_end__
mov r2, #0
bl memory_set
/* Zereo the privileged data. */
ldr r0, =__privileged_data_start__
ldr r1, =__privileged_data_end__
mov r2, #0
bl memory_set
/* Initialise the heap */
ldr r0, = __heap_start__
ldr r1, = __heap_end__
sub r1, r1, r0
mov r2, #0
str r2, [r0]
add r0, r0, #4
str r1, [r0]
/* Call constructors */
ldr r0, =__ctors_start__
ldr r1, =__ctors_end__
ctor_loop:
cmp r0, r1
beq ctor_end
ldr r2, [r0]
add r0, #4
push {r0-r1}
blx r2
pop {r0-r1}
b ctor_loop
ctor_end:
/* Setup initial call frame */
mov r0, #0
mov lr, r0
mov r12, sp
start:
/* Jump to application entry point */
#ifdef FULL_LIBRARY
mov r0, #ARGSSPACE
ldr r1, =args
ldr r2, =debug_getargs
blx r2
ldr r1, =args
#else
mov r0, #0
mov r1, #0
#endif
ldr r2, =APP_ENTRY_POINT
blx r2
#ifdef FULL_LIBRARY
.thumb_func
exit:
mov r5, r0 // save the exit parameter/return result
/* Call destructors */
ldr r0, =__dtors_start__
ldr r1, =__dtors_end__
dtor_loop:
cmp r0, r1
beq dtor_end
ldr r2, [r0]
add r0, #4
push {r0-r1}
blx r2
pop {r0-r1}
b dtor_loop
dtor_end:
/* Call atexit functions */
ldr r2, =_execute_at_exit_fns
blx r2
/* Call debug_exit with return result/exit parameter */
mov r0, r5
ldr r2, =debug_exit
blx r2
#endif
/* Returned from application entry point, loop forever. */
exit_loop:
b exit_loop
memory_copy:
cmp r0, r1
beq 2f
subs r2, r2, r1
beq 2f
1:
ldrb r3, [r0]
add r0, r0, #1
strb r3, [r1]
add r1, r1, #1
subs r2, r2, #1
bne 1b
2:
bx lr
memory_set:
cmp r0, r1
beq 1f
strb r2, [r0]
add r0, r0, #1
b memory_set
1:
bx lr
#ifdef FULL_LIBRARY
.bss
args:
.space ARGSSPACE
#endif
Loading…
Cancel
Save