Merge new ARM port submitted by navaro, with modifications to fit with the other Atomthreads ports, new folder structure, Makefiles and documentation. Tested on ARM926EJS using IntegratorCP platform emulated by QEMU.

Also minor changes to AVR/STM8 ports to use similar code structure throughout all ports.
This commit is contained in:
Kelvin Lawson
2013-07-09 22:06:10 +01:00
parent 5181143343
commit 5d3f670ac0
26 changed files with 4512 additions and 7 deletions

View File

@@ -44,8 +44,10 @@ struct atom_tcb;
typedef struct atom_tcb
{
/* Thread's current stack pointer. When a thread is scheduled
* out the architecture port can save*/
/*
* Thread's current stack pointer. When a thread is scheduled
* out the architecture port can save its stack pointer here.
*/
POINTER sp_save_ptr;
/* Thread priority (0-255) */

1161
ports/arm/Doxyfile Normal file

File diff suppressed because it is too large Load Diff

107
ports/arm/README Normal file
View File

@@ -0,0 +1,107 @@
---------------------------------------------------------------------------
Library: Atomthreads ARM Port
Author: Natie van Rooyen <natie@navaro.nl>
License: BSD Revised
---------------------------------------------------------------------------
ARM PORT
This folder contains a port of the Atomthreads real time kernel for the
ARM processor architecture. This port was tested on the ARMv5 and ARMv7
architectures.
The same common/core port can be used on a wide variety of ARM devices
but platform-specific code has been separated out into multiple "platform"
(BSP) folders. This allows the common ARM code to be shared among several
different ARM platforms and boards. For example, different ARM devices and
platforms might use different interrupt controllers, timer subsystems and
UARTs but share the same core OS context-switching routines etc.
An example platform is in the "platforms/qemu_integratorcp" folder. The
platform-specific folders such as this contain the Makefile to build the
project for that platform, so you may wish to head straight there if you
wish to quickly get started building and running Atomthreads on ARM. The
qemu_integratorcp platform is designed for the Integrator/CP platform with
ARM926EJ-S processor, and can be run within QEMU for quick evaluation of
Atomthreads without real hardware.
---------------------------------------------------------------------------
FILES IN THE COMMON ARM PORT FOLDER
* tests-main.c: Contains a sample Atomthreads application starting at
main() that initialises the operating system and runs the automated test
suite applications. You will normally make your own main() function
suitable for your application, possibly using this as a basis.
* atomport-asm.s: Contains the main assembler code that forms the portion
of the core ARM architecture port that must be implemented in assembler
(e.g. register save/restore for thread context-switching).
* atomport.c: Contains the main C code that forms the portion of the core
ARM architecture port that can be implemented in C (e.g. prefilling the
stack context for new threads).
* syscalls.c: Contains the open/close/read/write/heap-management
functions typically required if you want to do anything with stdio
(e.g. printf() calls etc). This is a very simple implementation that
always writes to the UART regardless of which file is "opened". Use of
printf() and friends with GCC toolchains typically requires a heap, and
thus a heap is supported in this file via the _sbrk() function. Your
linker script should specify where the heap starts and stops using "end"
and "heap_top" definitions respectively. Note that in QEMU environments
this may not be required as some "semi-hosted" toolchains implement
these functions and the UART driver for you. In that case these
functions will be left out of the build because they are defined with
weak linkage.
---------------------------------------------------------------------------
PORTING TO NEW ARM PLATFORMS
To port Atomthreads to your ARM platform you must provide the following
functionality in your platform folder (in all cases example filenames are
from the qemu_integratorcp sample platform):
* Startup code: see Reset_Handler in startup.s. Typically this will be (at
least in the first few instructions) some assembly code, and will set up
the initial stack pointer, perform any copying of segments from flash to
RAM, zero the BSS section etc, before branching to the main application
function (e.g. main()). At some point during initialisation the timer
tick interrupt required by the OS should be started (100 ticks per
second) and this might be done here in the very early startup code. Note
that some compiler toolchains will provide a portion of the C startup
code e.g. the function _mainCRTStartup() provided by some GCC
toolchains.
* Interrupt vector table: see __interrupt_vector_table in startup.s.
Typically this will contain at least an entry for the startup/reset
code, and an entry for the hardware IRQ handler. In order to share
common code amongst all platforms, the hardware IRQ handler
(archIRQHandler()) is actually implemented in the common ARM port
folder but calls back out to a dispatcher function in your platform
folder to determine the source of the interrupt and handle it
appropriately. Your platform folder should contain this dispatcher
function (__interrupt_dispatcher). It must support at least the timer
interrupt service routine (atomTimerTick()) required by the OS. The
dispatcher also handles other hardware interrupt sources; it determines
the source of the IRQ and calls out to the appropriate ISR for that
interrupt.
* Linker script: Here you should specify the location of the interrupt
vector table within RAM, location of code/text segment etc. The
Atomthreads ARM port does not dictate particular section names or
layout unless your toolchain does not provide a suitable syscalls.c and
you wish to use heap. In that case you will (at least initially) be
using the heap implementation _sbrk() in syscalls.c in the common ARM
port which expects "heap_top" and "end" (heap_base) to be defined by the
linker script. These names can be easily changed in ports/arm/syscalls.c
if necessary.
* UART driver: You should provide at least a UART write routine If you
would like to see debug statements, for example to see the results of
running the automated test suite. See uart.c for a simple example. Note
that for QEMU targets some semihosted toolchains will implement this for
you, in which case you won't need either ports/arm/syscalls.c or a UART
driver.
---------------------------------------------------------------------------

210
ports/arm/atomport-asm.s Normal file
View File

@@ -0,0 +1,210 @@
/*
Copyright (c) 2012, Natie van Rooyen. All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions
are met:
1. Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
3. No personal names or organizations' names associated with the
Atomthreads project may be used to endorse or promote products
derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE ATOMTHREADS PROJECT AND CONTRIBUTORS
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE PROJECT OR CONTRIBUTORS 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.
*/
/**/
.global archIRQHandler
.global contextEnterCritical
.global contextExitCritical
.global contextEnableInterrupts
.global archContextSwitch
.global archFirstThreadRestore
.extern __interrupt_dispatcher
/**/
.equ USR_MODE, 0x10
.equ FIQ_MODE, 0x11
.equ IRQ_MODE, 0x12
.equ SVC_MODE, 0x13
.equ ABT_MODE, 0x17
.equ UND_MODE, 0x1B
.equ SYS_MODE, 0x1F
.equ I_BIT, 0x80 /* when I bit is set, IRQ is disabled */
.equ F_BIT, 0x40 /* when F bit is set, FIQ is disabled */
.text
.code 32
/*
* \b archContextSwitch
*
* Architecture-specific context switch routine.
*
* Note that interrupts are always locked out when this routine is
* called. For cooperative switches, the scheduler will have entered
* a critical region. For preemptions (called from an ISR), the
* ISR will have disabled interrupts on entry.
*
* @param[in] old_tcb_ptr Pointer to the thread being scheduled out
* @param[in] new_tcb_ptr Pointer to the thread being scheduled in
*
* @return None
*
* void archContextSwitch (ATOM_TCB *old_tcb_ptr, ATOM_TCB *new_tcb_ptr)
*/
archContextSwitch:
STMFD sp!, {r4 - r11, lr} /* Save registers */
STR sp, [r0] /* Save old SP in old_tcb_ptr->sp_save_ptr (first TCB element) */
LDR r1, [r1] /* Load new SP from new_tcb_ptr->sp_save_ptr (first TCB element) */
MOV sp, r1
LDMFD sp!, {r4 - r11, pc} /* Load new registers */
/**
* \b archFirstThreadRestore
*
* Architecture-specific function to restore and start the first thread.
* This is called by atomOSStart() when the OS is starting.
*
* This function will be largely similar to the latter half of
* archContextSwitch(). Its job is to restore the context for the
* first thread, and finally enable interrupts (although we actually
* enable interrupts in thread_shell() for new threads in this port
* rather than doing it explicitly here).
*
* It expects to see the context saved in the same way as if the
* thread has been previously scheduled out, and had its context
* saved. That is, archThreadContextInit() will have been called
* first (via atomThreadCreate()) to create a "fake" context save
* area, containing the relevant register-save values for a thread
* restore.
*
* Note that you can create more than one thread before starting
* the OS - only one thread is restored using this function, so
* all other threads are actually restored by archContextSwitch().
* This is another reminder that the initial context set up by
* archThreadContextInit() must look the same whether restored by
* archFirstThreadRestore() or archContextSwitch().
*
* @param[in] new_tcb_ptr Pointer to the thread being scheduled in
*
* @return None
*
* void archFirstThreadRestore (ATOM_TCB *new_tcb_ptr)
*/
archFirstThreadRestore:
LDR r0, [r0] /* Get SP (sp_save_ptr is conveniently first element of TCB) */
MOV sp, r0 /* Load new stack pointer */
LDMFD sp!, {r4 - r11, pc} /* Load new registers */
/**
* \b contextEnableInterrupts
*
* Enables interrupts on the processor
*
* @return None
*/
contextEnableInterrupts:
MRS r0, CPSR
MOV r1, #I_BIT
BIC r0, r0, r1
MSR CPSR_c, r0
BX lr
/**
* \b contextExitCritical
*
* Exit critical section (restores interrupt posture)
*
* @param[in] r0 Interrupt Posture
*
* @return None
*/
contextExitCritical:
MSR CPSR_cxsf, r0
BX lr
/**
* \b contextEnterCritical
*
* Enter critical section (disables interrupts)
*
* @return Current interrupt posture
*/
contextEnterCritical:
MRS r0, CPSR
ORR r1, r0, #I_BIT
MSR CPSR_cxsf, r1
BX lr
/**
* \b archIRQHandler
*
* IRQ entry point.
*
* Save the process/thread context onto its own stack before calling __interrupt_dispatcher().
* __interrupt_dispatcher() might switch stacks. On return the same context is popped from the
* stack and control is returned to the process.
*
* @return None
*/
archIRQHandler:
MSR cpsr_c, #(SVC_MODE | I_BIT) /* Save current process context in process stack */
STMFD sp!, {r0 - r3, ip, lr}
MSR cpsr_c, #(IRQ_MODE | I_BIT) /* Save lr_irq and spsr_irq in process stack */
SUB lr, lr, #4
MOV r1, lr
MRS r2, spsr
MSR cpsr_c, #(SVC_MODE | I_BIT)
STMFD sp!, {r1, r2}
BL __interrupt_dispatcher /* Dispatch the interrupt to platform folder for
the timer tick interrupt or a simular function
for other interrupts. Some of those IRQs may
call Atomthreads kernel routines and cause a
thread switch. */
LDMFD sp!, {r1, r2} /* Restore lr_irq and spsr_irq from process stack */
MSR cpsr_c, #(IRQ_MODE | I_BIT)
STMFD sp!, {r1}
MSR spsr_cxsf, r2
MSR cpsr_c, #(SVC_MODE | I_BIT) /* Restore process regs */
LDMFD sp!, {r0 - r3, ip, lr}
MSR cpsr_c, #(IRQ_MODE | I_BIT) /* Exit from IRQ */
LDMFD sp!, {pc}^

View File

@@ -0,0 +1,40 @@
/*
* Copyright (c) 2012, Natie van Rooyen. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. No personal names or organizations' names associated with the
* Atomthreads project may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE ATOMTHREADS PROJECT AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
* TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE PROJECT OR CONTRIBUTORS 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.
*/
#ifndef __ATOM_PORT_PRIVATE_H
#define __ATOM_PORT_PRIVATE_H
/* Function prototypes */
extern void archIRQHandler (void);
/* Platform-specific interrupt dispatcher called on receipt of IRQ */
extern void __interrupt_dispatcher (void);
#endif /* __ATOM_PORT_PRIVATE_H */

View File

@@ -0,0 +1,59 @@
/*
* Copyright (c) 2012, Natie van Rooyen. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. No personal names or organizations' names associated with the
* Atomthreads project may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE ATOMTHREADS PROJECT AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
* TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE PROJECT OR CONTRIBUTORS 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.
*/
#ifndef __ATOM_PORT_TESTS_H
#define __ATOM_PORT_TESTS_H
/* Include Atomthreads kernel API */
#include "atom.h"
/* Include printf for ATOMLOG() */
#include <stdio.h>
/* Logger macro for viewing test results */
#define ATOMLOG printf
/*
* String location macro: for platforms which need to place strings in
* alternative locations, e.g. on avr-gcc strings can be placed in
* program space, saving SRAM. On most platforms this can expand to
* empty.
*/
#define _STR(x) x
/* Default thread stack size (in bytes). Allow plenty for printf(). */
#define TEST_THREAD_STACK_SIZE 4096
/* Uncomment to enable logging of stack usage to UART */
/* #define TESTS_LOG_STACK_USAGE */
#endif /* __ATOM_PORT_TESTS_H */

157
ports/arm/atomport.c Normal file
View File

@@ -0,0 +1,157 @@
/*
* Copyright (c) 2013, Natie van Rooyen. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. No personal names or organizations' names associated with the
* Atomthreads project may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE ATOMTHREADS PROJECT AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
* TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE PROJECT OR CONTRIBUTORS 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.
*/
#include "atom.h"
#include "atomport.h"
/** Functions defined in atomport_s.s */
extern void contextEnableInterrupts (void);
/** Forward declarations */
static void thread_shell (void);
/**
* \b thread_shell
*
* Shell routine which is used to call all thread entry points.
*
* This routine is called whenever a new thread is starting, and
* provides a simple wrapper around the thread entry point that
* allows us to carry out any actions we want to do on thread's
* first starting up, or returning after completion.
*
* We mainly just want to make sure interrupts are enabled when a
* thread is run for the first time. This can be done via stack
* restores when threads are first run, but it's handy to have this
* wrapper anyway to run some common code if threads run to
* completion.
*
* A thread shell is also handy for providing port users with a place
* to do any other initialisation that must be done for each thread
* (e.g. opening stdio files etc).
*
* @return None
*/
static void thread_shell (void)
{
ATOM_TCB *curr_tcb;
/* Get the TCB of the thread being started */
curr_tcb = atomCurrentContext();
/**
* Enable interrupts - these will not be enabled when a thread
* is first restored.
*/
contextEnableInterrupts ();
/* Call the thread entry point */
if (curr_tcb && curr_tcb->entry_point)
{
curr_tcb->entry_point(curr_tcb->entry_param);
}
/* Thread has run to completion: remove it from the ready list */
curr_tcb->suspended = TRUE;
atomSched (FALSE);
}
/**
* \b archThreadContextInit
*
* Architecture-specific thread context initialisation routine.
*
* This function must set up a thread's context ready for restoring
* and running the thread via archFirstThreadRestore() or
* archContextSwitch().
*
* The layout required to fill the correct register values is
* described in archContextSwitch(). Note that not all registers
* are restored by archContextSwitch() and archFirstThreadRestore()
* as this port takes advantage of the fact that not all registers
* must be stored by ARM gcc C subroutines. This means that we don't
* provide start values for those registers, as they are "don't cares".
*
* @param[in] tcb_ptr Pointer to the TCB of the thread being created
* @param[in] stack_top Pointer to the top of the new thread's stack
* @param[in] entry_point Pointer to the thread entry point function
* @param[in] entry_param Parameter to be passed to the thread entry point
*
* @return None
*/
void archThreadContextInit (ATOM_TCB *tcb_ptr, void *stack_top, void (*entry_point)(uint32_t), uint32_t entry_param)
{
uint32_t *stack_ptr;
/** Start at stack top */
tcb_ptr->sp_save_ptr = stack_ptr = stack_top;
/**
* After restoring all of the context registers, the thread restore
* routines will return to the address of the calling routine on the
* stack. In this case (the first time a thread is run) we "return"
* to the entry point for the thread. That is, we store the thread
* entry point in the place that return will look for the return
* address: the stack.
*
* Note that we are using the thread_shell() routine to start all
* threads, so we actually store the address of thread_shell()
* here. Other ports may store the real thread entry point here
* and call it directly from the thread restore routines.
*
* Because we are filling the stack from top to bottom, this goes
* on the stack first (at the top).
*/
*stack_ptr-- = (uint32_t)thread_shell;
/**
* Store starting register values for R4-R11
*/
*stack_ptr-- = (uint32_t) 0x00001111; /* R11 */
*stack_ptr-- = (uint32_t) 0x00001010; /* R10 */
*stack_ptr-- = (uint32_t) 0x00000909; /* R9 */
*stack_ptr-- = (uint32_t) 0x00000808; /* R8 */
*stack_ptr-- = (uint32_t) 0x00000707; /* R7 */
*stack_ptr-- = (uint32_t) 0x00000606; /* R6 */
*stack_ptr-- = (uint32_t) 0x00000505; /* R5 */
*stack_ptr = (uint32_t) 0x00000404; /* R4 */
/**
* All thread context has now been initialised. Save the current
* stack pointer to the thread's TCB so it knows where to start
* looking when the thread is started.
*/
tcb_ptr->sp_save_ptr = stack_ptr;
}

76
ports/arm/atomport.h Normal file
View File

@@ -0,0 +1,76 @@
/*
* Copyright (c) 2012, Natie van Rooyen. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. No personal names or organizations' names associated with the
* Atomthreads project may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE ATOMTHREADS PROJECT AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
* TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE PROJECT OR CONTRIBUTORS 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.
*/
#ifndef __ATOM_PORT_H
#define __ATOM_PORT_H
/* Portable uint8_t and friends available from stdint.h on this platform */
#include <stdint.h>
/* Definition of NULL is available from stddef.h on this platform */
#include <stddef.h>
/* Required number of system ticks per second (normally 100 for 10ms tick) */
#define SYSTEM_TICKS_PER_SEC 100
/* Size of each stack entry / stack alignment size (32 bits on this platform) */
#define STACK_ALIGN_SIZE sizeof(uint32_t)
/**
* Architecture-specific types.
* Most of these are available from stdint.h on this platform, which is
* included above.
*/
#define POINTER void *
/* *
*
* Functions defined in atomport_arm.asm
*
*/
extern uint32_t contextEnterCritical (void) ;
extern void contextExitCritical (uint32_t posture) ;
/**
* Critical region protection: this should disable interrupts
* to protect OS data structures during modification. It must
* allow nested calls, which means that interrupts should only
* be re-enabled when the outer CRITICAL_END() is reached.
*/
#define CRITICAL_STORE uint32_t __atom_critical
#define CRITICAL_START() __atom_critical = contextEnterCritical()
#define CRITICAL_END() contextExitCritical(__atom_critical)
/* Uncomment to enable stack-checking */
/* #define ATOM_STACK_CHECKING */
#endif /* __ATOM_PORT_H */

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,129 @@
############
# Settings #
############
# Build all test applications:
# make
#
# Run all tests within QEMU
# make qemutests
# Location of build tools and atomthreads sources
KERNEL_DIR=../../../../kernel
TESTS_DIR=../../../../tests
PORT_DIR=../..
CC=arm-none-eabi-gcc
OBJCOPY=arm-none-eabi-objcopy
QEMU=qemu-system-arm
# Enable stack-checking.
#STACK_CHECK=true
# Test programs: Log stack usage to UART (if STACK_CHECK is enabled)
#TESTS_LOG_STACK=true
# Directory for built objects
BUILD_DIR=build
# Platform-specific object files
PLATFORM_OBJECTS = modules.o uart.o
PLATFORM_ASM_OBJECTS = startup.o
# Port-specific object files
PORT_OBJECTS = atomport.o tests-main.o syscalls.o
PORT_ASM_OBJECTS = atomport-asm.o
# Kernel object files
KERNEL_OBJECTS = atomkernel.o atomsem.o atommutex.o atomtimer.o atomqueue.o
# Collection of built objects (excluding test applications)
ALL_OBJECTS = $(PLATFORM_OBJECTS) $(PLATFORM_ASM_OBJECTS) $(PORT_OBJECTS) $(PORT_ASM_OBJECTS) $(KERNEL_OBJECTS)
BUILT_OBJECTS = $(patsubst %,$(BUILD_DIR)/%,$(ALL_OBJECTS))
# Test object files (dealt with separately as only one per application build)
TEST_OBJECTS = $(notdir $(patsubst %.c,%.o,$(wildcard $(TESTS_DIR)/*.c)))
# Target application filenames for each test object
TEST_ELFS = $(patsubst %.o,%.elf,$(TEST_OBJECTS))
# Search build/output directory for dependencies
vpath %.o ./$(BUILD_DIR)
vpath %.elf ./$(BUILD_DIR)
# GCC flags
CFLAGS=-g -c -mcpu=arm926ej-s -ffreestanding -Wall -Werror
AFLAGS=$(CFLAGS) -x assembler-with-cpp
LFLAGS=-mcpu=arm926ej-s -Tsystem.ld -Wall
# Enable stack-checking options (disable if not required)
ifeq ($(STACK_CHECK),true)
CFLAGS += -DATOM_STACK_CHECKING
endif
ifeq ($(TESTS_LOG_STACK),true)
CFLAGS += -DTESTS_LOG_STACK_USAGE
endif
#################
# Build targets #
#################
# All tests
all: $(BUILD_DIR) $(TEST_ELFS) Makefile
# Make build/output directory
$(BUILD_DIR):
mkdir $(BUILD_DIR)
# Test ELF files (one application build for each test)
$(TEST_ELFS): %.elf: %.o $(ALL_OBJECTS)
$(CC) $(LFLAGS) $(BUILD_DIR)/$(notdir $<) $(BUILT_OBJECTS) --output $(BUILD_DIR)/$@ -Wl,-Map,$(BUILD_DIR)/$(basename $@).map
# Kernel objects builder
$(KERNEL_OBJECTS): %.o: $(KERNEL_DIR)/%.c
$(CC) -c $(CFLAGS) -I. -I$(PORT_DIR) $< -o $(BUILD_DIR)/$(notdir $@)
# Test objects builder
$(TEST_OBJECTS): %.o: $(TESTS_DIR)/%.c
$(CC) -c $(CFLAGS) -I. -I$(PORT_DIR) -I$(KERNEL_DIR) $< -o $(BUILD_DIR)/$(notdir $@)
# Platform C objects builder
$(PLATFORM_OBJECTS): %.o: ./%.c
$(CC) -c $(CFLAGS) -I. -I$(PORT_DIR) -I$(KERNEL_DIR) -I$(TESTS_DIR) $< -o $(BUILD_DIR)/$(notdir $@)
# Platform asm objects builder
$(PLATFORM_ASM_OBJECTS): %.o: ./%.s
$(CC) -c $(AFLAGS) -I. -I$(PORT_DIR) -I$(KERNEL_DIR) $< -o $(BUILD_DIR)/$(notdir $@)
# Port C objects builder
$(PORT_OBJECTS): %.o: $(PORT_DIR)/%.c
$(CC) -c $(CFLAGS) -I. -I$(PORT_DIR) -I$(KERNEL_DIR) -I$(TESTS_DIR) $< -o $(BUILD_DIR)/$(notdir $@)
# Port asm objects builder
$(PORT_ASM_OBJECTS): %.o: $(PORT_DIR)/%.s
$(CC) -c $(AFLAGS) -I. -I$(PORT_DIR) -I$(KERNEL_DIR) $< -o $(BUILD_DIR)/$(notdir $@)
# .lst file builder
%.lst: %.c
$(CC) $(CFLAGS) -I. -I$(PORT_DIR) -I$(KERNEL_DIR) -I$(TESTS_DIR) -Wa,-al $< > $@
# Clean
clean:
rm -f *.o *.elf *.map *.lst
rm -rf doxygen-kernel
rm -rf doxygen-arm
rm -rf doxygen-platform
rm -rf build
# Generate Doxygen documentation
doxygen:
doxygen $(KERNEL_DIR)/Doxyfile
doxygen ../../Doxyfile
doxygen ./Doxyfile
# Run tests within simavr simulator
phony_qemu_elfs = $(addsuffix .sim, $(TEST_ELFS))
qemutests: $(phony_qemu_elfs)
.PHONY: qemutests $(phony_qemu_elfs)
$(phony_qemu_elfs):
./run_test.exp $(QEMU) $(BUILD_DIR)/$(basename $@)

View File

@@ -0,0 +1,223 @@
---------------------------------------------------------------------------
Library: Atomthreads QEMU ARM Integrator/CP (ARM926EJ-S) Platform.
Author: Natie van Rooyen <natie@navaro.nl>
Website: http://atomthreads.com
License: BSD Revised
---------------------------------------------------------------------------
QEMU ARM Integrator/CP (ARM926EJ-S) Platform
The "qemu_integratorcp" platform folder contains sources for building a
sample Atomthreads application for the ARM Integrator/CP (ARM926EJ-S)
platform running under QEMU.
All of the cross-platform kernel code is contained in the top-level
'kernel' folder, while ports to specific CPU architectures are contained in
the 'ports' folder tree. To support multiple ARM boards/platforms using a
single common ARM architecture port, the ARM port contains 'platform'
sub-folders in which the board/platform-specific code is situated. This
allows the sharing of common ARM port code between many different ARM
boards with different interrupt controllers, UARTs etc but which all reuse
the same common core ARM context-switching code.
This platform contains a few key platform-specific files:
* startup.s: Interrupt vector table and basic startup assembly code
* modules.c: Low level initialisation for this platform
* uart.c: Simple UART implementation for debug purposes
The common ARM architecture port that is used across all platforms contains
the basic code for thread-switching on all ARM platforms:
* atomport.c: Those functions which can be written in C
* atomport-asm.s: The main register save/restore assembler routines
Each Atomthreads port requires also a header file which describes various
architecture-specific details such as appropriate types for 8-bit, 16-bit
etc variables, the port's system tick frequency, and macros for performing
interrupt lockouts / critical sections:
* atomport.h: Port-specific header required by the kernel for each port
A couple of additional source files are also included in the common ARM port:
* tests-main.c: Main application file (used for launching automated tests)
* syscalls.c: Simple implementation of open/close/read/write for stdio
Atomthreads includes a suite of automated tests which prove the key OS
functionality, and can be used with any architecture ports. This port
provides an easy mechanism for building and quickly running the test suite
using QEMU to prove the OS without requiring any target hardware.
This platform folder has been tested on a variety of GCC ARM toolchains,
including hosted and non-hosted.
---------------------------------------------------------------------------
GCC TOOLCHAIN
The port works out-of-the-box with the GCC tools (for building) and QEMU
(for simulation). It can be built on any OS for which GCC is available, and
was tested using the CodeSourcery toolchain (2009q3 non-Linux but others
should be supported) and self-built toolchains such as hosted toolchains
built by build_arm_toolchain.sh (see http://navaro.nl for details). Note
that the Makefile for this platform assumes that your GCC binary is named
"arm-none-eabi-gcc".
Currently we assume that the toolchain will provide some header files like
stdint.h. Not all toolchains will include this, in which case you simply
need to add definitions for int32_t and friends in atomport.h, in place of
the include declaration for stdint.h.
Some toolchains provide newlib syscalls.c which implement stdio
functionality via open, close, read, write. Hosted toolchains will
automatically provide versions of these which work with QEMU, and no UART
driver will be needed to view the stdio printf()s etc. If these are not
provided by by the compiler toolchain then backup implementations are
implemented within the common ARM port folder (see ports/arm/syscalls.c)
and a UART driver is implemented here in uart.c.
Similarly some toolchains provide startup assembly code via
_mainCRTStartup(). If this is not provided by the toolchain then a backup
version is used within modules.c.
---------------------------------------------------------------------------
OTHER PREREQUISITES
QEMU is used for simulation of the target and versions 0.14.1, 1.2.0 &
1.4.0 were tested.
Running the entire automated test suite in one command via "make qemutests"
also requires the "expect" program.
---------------------------------------------------------------------------
BUILDING THE SOURCE
A Makefile is provided for building the kernel, port, platform and
automated tests. Make sure the ARM GCC toolchain is in the path
(e.g. "PATH=$PATH:/opt/arm-2009q3/bin && export path") as well as QEMU and
carry out the full build using the following:
* make all
All objects are built into the 'build' folder under
ports/arm/platforms/qemu_integrator_cp. The build process builds separate
target applications for each automated test, and appropriate ELF files can
be found in the build folder ready for running on the target or within
QEMU. Each test is built and run as a separate application.
All built objects etc can be cleaned using:
* make clean
The Atomthreads sources are documented using Doxygen markup. You can build
both the kernel and port documentation from this folder using:
* make doxygen
---------------------------------------------------------------------------
Integrator/CP SPECIFICS
The test applications make use of the Integrator's UART to print out
pass/fail indications and other information. For this you should connect a
serial debug cable to the board or when running in QEMU you will see the
UART messages on the console when running the test applications.
---------------------------------------------------------------------------
AUTOMATED TESTS
Atomthreads contains a set of generic kernel tests which can be run on any
port to prove that all core functionality is working on your target.
The full set of tests can be found in the top-level 'tests' folder. Each of
these tests is built as an independent application in the 'build' folder.
These can be run on the target or within QEMU using the instructions below.
To view the test results, connect a serial debug cable to your target
platform or view the console if using QEMU. On starting, the test
applications print out "Go" on the UART. Once the test is complete they
will print out "Pass" or "Fail", along with other information if the test
failed.
Most of the tests complete within a few seconds, but some (particularly
the stress tests) can take longer, so be patient.
The full suite of tests endeavours to exercise as much of the kernel code
as possible, and can be used for quick confirmation of core OS
functionality if you ever need to make a change to the kernel or port.
The test application main() is contained in tests-main.c. This initialises
the OS, creates a main thread, and calls out to the test modules.
---------------------------------------------------------------------------
RUNNING TESTS WITHIN THE QEMU SIMULATOR
It is possible to run the full automated test suite in a simulator without
programming the test applications into real hardware. This is very useful
for quick verification of the entire test suite after making any software
changes, and is much faster than downloading each test application to a
real target.
A single command runs every single test application, and automatically
parses the (simulated) UART output to verify that each test case passes.
This requires two applications on your development PC: expect and QEMU.
To run all tests in one command, type:
* make qemutests
This will run every single test application within the simulator and quit
immediately if any one test fails.
The ability to run these automated tests in one command (and without real
hardware) allows you to easily include the OS test suite in your nightly
build or continous integration system and quickly find out if any of your
local changes have caused any of the operating system tests to fail.
---------------------------------------------------------------------------
DEBUGGING WITH QEMU
You may also use QEMU in combination with GDB to debug your built
applications. To do this you should start QEMU with "-S -s" options e.g.:
* qemu-system-arm -M integratorcp -semihosting -nographic -kernel app.elf
You can now start GDB and attach to the target:
* arm-none-eabi-gdb
* file app.elf
* target remote localhost:1234
---------------------------------------------------------------------------
WRITING APPLICATIONS
The easiest way to start a new application which utilises the Atomthreads
scheduler is to base your main application startup on tests-main.c. This
initialises the OS and calls out to the test module entry functions. You
can generally simply replace the call to the test modules by a call to your
own application startup code.
---------------------------------------------------------------------------

View File

@@ -0,0 +1,163 @@
/*
* Copyright (c) 2012, Natie van Rooyen. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. No personal names or organizations' names associated with the
* Atomthreads project may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE ATOMTHREADS PROJECT AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
* TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE PROJECT OR CONTRIBUTORS 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.
*/
#include "modules.h"
#include <stdio.h>
#include <stdarg.h>
#include "atomport.h"
#include "atomport-private.h"
#include "atom.h"
#include "atomport.h"
#include "uart.h"
/** Imports required by C startup code */
extern unsigned long _end_text, _start_data, _end_data, _start_bss, _end_bss;
extern int main(void);
/** Board-specific registers */
ICP_TIMER_T * const board_timer_0 = (ICP_TIMER_T*)BOARD_BASE_ADDRESS_TIMER_0;
ICP_PIC_T * const board_pic = (ICP_PIC_T*)BOARD_BASE_ADDRESS_PIC;
/** TIMER0 clock speed (Hz) */
#define TIMER0_CLOCK_SPEED 40000000
/**
* \b _mainCRTStartup
*
* C startup code for environments without a suitable built-in one.
* May be provided by the compiler toolchain in some cases.
*
*/
extern void _mainCRTStartup (void) __attribute__((weak));
void _mainCRTStartup(void)
{
unsigned long *src;
#ifdef ROM
unsigned long *dst;
#endif
#ifdef ROM
// Running from ROM: copy data section to RAM
src = &_end_text;
dst = &_start_data;
while(dst < &_end_data)
*(dst++) = *(src++);
#endif
// Clear BSS
src = &_start_bss;
while(src < &_end_bss)
*(src++) = 0;
// Jump to main application entry point
main();
}
/**
* \b low_level_init
*
* Initializes the PIC and starts the system timer tick interrupt.
*
*/
int
low_level_init (void)
{
board_pic->IRQ_ENABLECLR = ICP_PIC_IRQ_TIMERINT0 ;
board_timer_0->INTCLR = 1 ;
board_pic->IRQ_ENABLESET |= ICP_PIC_IRQ_TIMERINT0 ;
/* Set the timer to go off 100 times per second (input clock speed is 40MHz) */
board_timer_0->LOAD = TIMER0_CLOCK_SPEED / SYSTEM_TICKS_PER_SEC ;
board_timer_0->BGLOAD = TIMER0_CLOCK_SPEED / SYSTEM_TICKS_PER_SEC ;
board_timer_0->CONTROL = ICP_TIMER_CONTROL_ENABLE |
ICP_TIMER_CONTROL_MODE |
ICP_TIMER_CONTROL_IE |
ICP_TIMER_CONTROL_TIMER_SIZE ;
return 0 ;
}
/**
* \b __interrupt_dispatcher
*
* Interrupt dispatcher: determines the source of the IRQ and calls
* the appropriate ISR.
*
* Currently only the OS system tick ISR is implemented.
*
* Note that any ISRs which call Atomthreads OS routines that can
* cause rescheduling of threads must be surrounded by calls to
* atomIntEnter() and atomIntExit().
*
*/
void
__interrupt_dispatcher (void)
{
unsigned int status;
/* Read STATUS register to determine the source of the interrupt */
status = board_pic->IRQ_STATUS;
/* Timer tick interrupt (call Atomthreads timer tick ISR) */
if (status | ICP_PIC_IRQ_TIMERINT0)
{
/*
* Let the Atomthreads kernel know we're about to enter an OS-aware
* interrupt handler which could cause scheduling of threads.
*/
atomIntEnter();
/* Call the OS system tick handler */
atomTimerTick();
/* Ack the interrupt */
board_timer_0->INTCLR = 0x1;
/* Call the interrupt exit routine */
atomIntExit(TRUE);
}
}
/**
* \b null_handler
*
* Handler to catch interrupts at uninitialised vectors.
*
*/
void null_handler (void)
{
uart_write_halt ("Unhandled interrupt\n");
}

View File

@@ -0,0 +1,126 @@
/*
* Copyright (c) 2012, Natie van Rooyen. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. No personal names or organizations' names associated with the
* Atomthreads project may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE ATOMTHREADS PROJECT AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
* TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE PROJECT OR CONTRIBUTORS 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.
*/
#ifndef __MODULES_H__
#define __MODULES_H__
/*
* Module definitions to use with the ARM Integrator/CP (ARM926EJ-S)
*/
#include "atomport.h"
/* IO definitions (access restrictions to peripheral registers) */
#define __I volatile /*!< defines 'read only' permissions */
#define __O volatile /*!< defines 'write only' permissions */
#define __IO volatile /*!< defines 'read / write' permissions */
// *****************************************************************************
// INTEGRATORCP TIMER
// *****************************************************************************
typedef struct ICP_TIMER_S {
// offset read/write word size reset Description
__IO uint32_t LOAD ; // 0x0000 Read/write 32 0x00000000 Load value for Timer
__I uint32_t VALUE ; // 0x0004 Read 32 0xFFFFFFFF The current value for Timer
__IO uint8_t CONTROL ; // 0x0008 Read/write 8 0x20 Timer control register
__O uint32_t INTCLR ; // 0x000C Write - - Timer interrupt clear
__I uint32_t RIS ; // 0x0010 Read 1 0x0 Timer raw interrupt status
__I uint32_t MIS ; // 0x0014 Read 1 0x0 Timer masked interrupt status
__IO uint32_t BGLOAD ; // 0x0018 Read/write 32 0x00000000 Background load value for Timer
} ICP_TIMER_T, *PICP_TIMER_T ;
// -------- ICP_TIMER_LOAD : (LOAD Offset: 0x00) Load value for Timer --------
// -------- ICP_TIMER_VALUE : (LOAD Offset: 0x04) The current value for Timer --------
// -------- ICP_TIMER_CONTROL : (CONTROL Offset: 0x04) Timer control register --------
#define ICP_TIMER_CONTROL_MASK ((unsigned int)0x0F << 0) // Timer control mask
#define ICP_TIMER_CONTROL_ENABLE ((unsigned int)0x01 << 7) // Timer enable: 0 = disabled 1 = enabled.
#define ICP_TIMER_CONTROL_MODE ((unsigned int)0x01 << 6) // Timer mode: 0 = free running, counts once and then wraps to 0xFFFF 1 = periodic, reloads from load register at the end of each count..
#define ICP_TIMER_CONTROL_IE ((unsigned int)0x01 << 5) // Interrupt enable.
#define ICP_TIMER_CONTROL_R ((unsigned int)0x01 << 4) // Unused, always write as 0s.
#define ICP_TIMER_CONTROL_PRESCALE_MASK ((unsigned int)0x03 << 2) // Prescale divisor
#define ICP_TIMER_CONTROL_PRESCALE_NONE ((unsigned int)0x00 << 2) //
#define ICP_TIMER_CONTROL_PRESCALE_16 ((unsigned int)0x01 << 2) //
#define ICP_TIMER_CONTROL_PRESCALE_256 ((unsigned int)0x02 << 2) //
#define ICP_TIMER_CONTROL_TIMER_SIZE ((unsigned int)0x01 << 1) // Selects 16/32 bit counter operation: 0 = 16-bit counter (default) 1 = 32-bit counter For 16-bit mode, write the high 16 bits of the 32-bit value as 0.
#define ICP_TIMER_CONTROL_ONE_SHOT ((unsigned int)0x01 << 0) // Selects one-shot or wrapping counter mode: 0 = wrapping mode (default) 1 = one-shot mode
// -------- ICP_TIMER_INTCLR : (INTCLR Offset: 0x0C) Timer interrupt clear --------
// -------- ICP_TIMER_RIS : (RIS Offset: 0x10) Timer raw interrupt status --------
// -------- ICP_TIMER_MIS : (MIS Offset: 0x14) Timer masked interrupt status --------
#define ICP_TIMER_INT ((unsigned int)0x01 << 0) // Interrupt
// -------- ICP_TIMER_BGLOAD : (BGLOAD Offset: 0x18) Timer masked interrupt status --------
// *****************************************************************************
// INTEGRATORCP PIC
// *****************************************************************************
typedef struct ICP_PIC_S {
// offset read/write word size reset Description
__I uint32_t IRQ_STATUS ; // 0x0000 Read 22 IRQ gated interrupt status
__I uint32_t IRQ_RAWSTAT ; // 0x0004 Read 22 IRQ raw interrupt status
__IO uint32_t IRQ_ENABLESET ; // 0x0008 Read/write 22 IRQ enable set
__O uint32_t IRQ_ENABLECLR ; // 0x000C Write 22 IRQ enable clear
__IO uint32_t INT_SOFTSET ; // 0x0010 Read/write 16 Software interrupt set
__O uint32_t INT_SOFTCLR ; // 0x0014 Write 16 Software interrupt clear
uint32_t RESERVED[2] ; // 0x0018
__I uint32_t FIQ_STATUS ; // 0x0020 Read 22 FIQ gated interrupt status
__I uint32_t FIQ_RAWSTAT ; // 0x0024 Read 22 FIQ raw interrupt status
__IO uint32_t FIQ_ENABLESET ; // 0x0028 Read/write 22 FIQ enable set
__O uint32_t FIQ_ENABLECLR ; // 0x002C Write-only 22 FIQ enable clear
} ICP_PIC_T, *PICP_PIC_T ;
// -------- ICP_PIC_IRQ_STATUS : (IRQ_STATUS Offset: 0x00) IRQ gated interrupt status --------
// -------- ICP_PIC_IRQ_RAWSTAT : (IRQ_RAWSTAT Offset: 0x04) IRQ raw interrupt status --------
// -------- ICP_PIC_IRQ_ENABLESET : (IRQ_ENABLESET Offset: 0x08) IRQ enable set --------
// -------- ICP_PIC_IRQ_ENABLECLR : (IRQ_ENABLECLR Offset: 0x0C) IRQ enable clear --------
#define ICP_PIC_IRQ_MASK ((unsigned int)0x3FFFFF << 0) // IRQ mask
#define ICP_PIC_IRQ_TIMERINT2 ((unsigned int)0x01 << 7) // TIMERINT2 Counter-timer 2 interrupt
#define ICP_PIC_IRQ_TIMERINT1 ((unsigned int)0x01 << 6) // TIMERINT1 Counter-timer 1 interrupt
#define ICP_PIC_IRQ_TIMERINT0 ((unsigned int)0x01 << 5) // TIMERINT0 Counter-timer 0 interrupt
#define ICP_PIC_IRQ_SOFTINT ((unsigned int)0x01 << 0) // OFTINT Software interrupt
// -------- ICP_PIC_INT_SOFTSET : (INT_SOFTSET Offset: 0x10) Software interrupt set --------
// -------- ICP_PIC_INT_SOFTCLR : (INT_SOFTCLR Offset: 0x14) Software interrupt clear --------
/* module definitions */
#define BOARD_BASE_ADDRESS_TIMER_0 0x13000000
#define BOARD_BASE_ADDRESS_PIC 0x14000000
extern ICP_TIMER_T* const board_timer_0 ;
extern ICP_PIC_T* const board_pic ;
/* Function prototypes */
extern int low_level_init (void) ;
#endif /* __MODULES_H__ */

View File

@@ -0,0 +1,39 @@
#!/usr/bin/env expect
# Expect script to run an automated test within QEMU and check for successful
# completion.
#
# Arguments: <path_to_qemu> <test_elf_file>
#
# Returns 0 on successful test run within QEMU, 1 on failure
# Start the test
spawn [lindex $argv 0] -M integratorcp -semihosting -nographic -kernel [lindex $argv 1]
# Expect to see the test starting within 10 seconds
set timeout 10
# Wait for the test to start ("Go")
expect {
"Go\r\n" {
puts "Test started"
# The test could take up to 3 minutes to complete once started
set timeout 180
# Now expect to see "Pass" or "Fail" within 3 minutes
expect {
"Pass\r\n" { puts "Test passed"; exit 0 }
"Fail\r\n" { puts "Test failed"; exit 1 }
timeout { puts "Test timed out without completing"; exit 1 }
}
}
timeout {
# Didn't receive "Go" within 10 seconds
puts "Test failed to start ('Go' not seen)"
exit 1
}
}

View File

@@ -0,0 +1,54 @@
.section .vectors, "x"
.global __interrupt_vector_table
.extern __irq_stack_top__
.extern __fiq_stack_top__
.extern __svc_stack_top__
.equ USR_MODE, 0x10
.equ FIQ_MODE, 0x11
.equ IRQ_MODE, 0x12
.equ SVC_MODE, 0x13
.equ ABT_MODE, 0x17
.equ UND_MODE, 0x1B
.equ SYS_MODE, 0x1F
.equ I_BIT, 0x80 /* when I bit is set, IRQ is disabled */
.equ F_BIT, 0x40 /* when F bit is set, FIQ is disabled */
__interrupt_vector_table:
B Reset_Handler /* Reset */
B Null_Handler /* Undefined */
B Null_Handler /* SWI */
B Null_Handler /* Prefetch Abort */
B Null_Handler /* Data Abort */
B Null_Handler /* reserved */
B IRQ_Handler /* IRQ */
B Null_Handler /* FIQ */
Reset_Handler:
MSR CPSR_c,#(IRQ_MODE | I_BIT | F_BIT)
LDR sp,=__irq_stack_top__ /* set the IRQ stack pointer */
MSR CPSR_c,#(FIQ_MODE | I_BIT | F_BIT)
LDR sp,=__fiq_stack_top__ /* set the FIQ stack pointer */
MSR CPSR_c,#(SVC_MODE | I_BIT | F_BIT)
LDR sp,=__svc_stack_top__ /* set the SVC stack pointer */
BL low_level_init
BL _mainCRTStartup
B .
IRQ_Handler:
B archIRQHandler
Null_Handler:
B null_handler

View File

@@ -0,0 +1,89 @@
ENTRY(__interrupt_vector_table)
MEMORY
{
flash (rx) : ORIGIN = 0x00000000, LENGTH = 0x00020000
sram (rwx) : ORIGIN = 0x00020000, LENGTH = 0x00020000
}
EXTERN(__interrupt_vector_table);
C_STACK_SIZE = 512;
IRQ_STACK_SIZE = 256;
FIQ_STACK_SIZE = 256;
SVC_STACK_SIZE = 512;
ABT_STACK_SIZE = 256;
UND_STACK_SIZE = 256;
SECTIONS
{
.text :
{
*(.vectors)
/* Startup assembly */
*(.startup)
*(.init)
/* Rest of the code (C) */
*(.text)
*(.rodata)
*(.rodata*)
_end_text = .;
} >flash
.data :
{
_start_data = .;
*(.data)
_end_data = .;
} >sram
.bss :
{
_start_bss = .;
__bss_start__ = . ;
*(.bss)
} >sram
. = ALIGN(4);
_end_bss = .;
__bss_end__ = . ;
. = ALIGN(256);
.stack : {
__stack_start__ = . ;
. += IRQ_STACK_SIZE;
. = ALIGN (4);
__irq_stack_top__ = . ;
. += FIQ_STACK_SIZE;
. = ALIGN (4);
__fiq_stack_top__ = . ;
. += SVC_STACK_SIZE;
. = ALIGN (4);
__svc_stack_top__ = . ;
. += ABT_STACK_SIZE;
. = ALIGN (4);
__abt_stack_top__ = . ;
. += UND_STACK_SIZE;
. = ALIGN (4);
__und_stack_top__ = . ;
. += C_STACK_SIZE;
. = ALIGN (4);
__c_stack_top__ = . ;
__stack_end__ = .;
} >sram
}
__end__ = .;
_end = .;
PROVIDE(end = .);
heap_top = ORIGIN(sram) + LENGTH(sram) - 4;

View File

@@ -0,0 +1,255 @@
/*
* Copyright (c) 2013, Kelvin Lawson. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. No personal names or organizations' names associated with the
* Atomthreads project may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE ATOMTHREADS PROJECT AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
* TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE PROJECT OR CONTRIBUTORS 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.
*/
/**
* \file
* Simple polled UART implementation for non-hosted compiler toolchains.
*
*
* This is only required for non-hosted toolchains which don't implement
* stdout automatically for use within QEMU.
*/
#include "atom.h"
#include "atommutex.h"
#include "atomport.h"
#include "uart.h"
/* Constants */
/** UART0 registers base address */
#define UART0_ADDR 0x16000000
/** FR Register bits */
#define UART_FR_RXFE 0x10
#define UART_FR_TXFF 0x20
/** UART register access macros */
#define UART_DR(baseaddr) (*(unsigned int *)(baseaddr))
#define UART_FR(baseaddr) (*(((unsigned int *)(baseaddr))+6))
/* Local data */
/*
* Semaphore for single-threaded access to UART device
*/
static ATOM_MUTEX uart_mutex;
/*
* Initialised flag
*/
static int initialised = FALSE;
/* Forward declarations */
static int uart_init (void);
/**
* \b uart_init
*
* Initialisation of UART driver. Creates a mutex that enforces
* single-threaded access to the UART. We poll register bits
* to check when space is available, which would not otherwise
* be thread-safe.
*
* @retval ATOM_OK Success
* @retval ATOM_ERROR Failed to create mutex
*/
static int uart_init (void)
{
int status;
/* Check we are not already initialised */
if (initialised == FALSE)
{
/* Create a mutex for single-threaded UART access */
if (atomMutexCreate (&uart_mutex) != ATOM_OK)
{
/* Mutex creation failed */
status = ATOM_ERROR;
}
else
{
/* Success */
initialised = TRUE;
status = ATOM_OK;
}
}
/* Finished */
return (status);
}
/**
* \b uart_read
*
* Simple polled UART read.
*
* @param[in] ptr Pointer to receive buffer
* @param[in] len Max bytes to read
*
* @retval Number of bytes read
*
*/
int uart_read (char *ptr, int len)
{
int todo = 0;
/* Check we are initialised */
if (initialised == FALSE)
{
uart_init();
}
/* Check parameters */
if ((ptr == NULL) || (len == 0))
{
return 0;
}
/* Block thread on private access to the UART */
if (atomMutexGet(&uart_mutex, 0) == ATOM_OK)
{
/* Wait for not-empty */
while(UART_FR(UART0_ADDR) & UART_FR_RXFE)
;
/* Read first byte */
*ptr++ = UART_DR(UART0_ADDR);
/* Loop over remaining bytes until empty */
for (todo = 1; todo < len; todo++)
{
/* Quit if receive FIFO empty */
if(UART_FR(UART0_ADDR) & UART_FR_RXFE)
{
break;
}
/* Read next byte */
*ptr++ = UART_DR(UART0_ADDR);
}
/* Return mutex access */
atomMutexPut(&uart_mutex);
}
/* Return number of bytes read */
return todo;
}
/**
* \b uart_write
*
* Simple polled UART write.
*
* @param[in] ptr Pointer to write buffer
* @param[in] len Number of bytes to write
*
* @retval Number of bytes written
*/
int uart_write (const char *ptr, int len)
{
int todo;
/* Check we are initialised */
if (initialised == FALSE)
{
uart_init();
}
/* Check parameters */
if ((ptr == NULL) || (len == 0))
{
return 0;
}
/* Block thread on private access to the UART */
if (atomMutexGet(&uart_mutex, 0) == ATOM_OK)
{
/* Loop through all bytes to write */
for (todo = 0; todo < len; todo++)
{
/* Wait for empty */
while(UART_FR(UART0_ADDR) & UART_FR_TXFF)
;
/* Write byte to UART */
UART_DR(UART0_ADDR) = *ptr++;
}
/* Return mutex access */
atomMutexPut(&uart_mutex);
}
/* Return bytes-written count */
return len;
}
/**
* \b uart_write_halt
*
* Simple polled UART write for handling critical failures
* by printing out a message on the UART and looping forever.
* Can be called from interrupt (unlike the standard
* uart_write()) but is not thread-safe because it cannot
* take the thread-safety mutex, and hence is only useful for
* a last-resort catastrophic debug message.
*
* @param[in] ptr Pointer to write string
*/
void uart_write_halt (const char *ptr)
{
/* Check parameters */
if (ptr != NULL)
{
/* Loop through all bytes until NULL terminator encountered */
while (*ptr != '\0')
{
/* Wait for empty */
while(UART_FR(UART0_ADDR) & UART_FR_TXFF)
;
/* Write byte to UART */
UART_DR(UART0_ADDR) = *ptr++;
}
}
/* Loop forever */
while (1)
;
}

View File

@@ -0,0 +1,38 @@
/*
* Copyright (c) 2013, Kelvin Lawson. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. No personal names or organizations' names associated with the
* Atomthreads project may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE ATOMTHREADS PROJECT AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
* TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE PROJECT OR CONTRIBUTORS 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.
*/
#ifndef __ATOM_UART_H
#define __ATOM_UART_H
/* UART driver APIs */
extern int uart_read (char *ptr, int len);
extern int uart_write (const char *ptr, int len);
extern void uart_write_halt (const char *ptr);
#endif /* __ATOM_UART_H */

211
ports/arm/syscalls.c Normal file
View File

@@ -0,0 +1,211 @@
/*
* Copyright (c) 2013, Kelvin Lawson. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. No personal names or organizations' names associated with the
* Atomthreads project may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE ATOMTHREADS PROJECT AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
* TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE PROJECT OR CONTRIBUTORS 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.
*/
/**
* \file
* Syscalls implementation for stdio and heap management.
*
*
* Simple implementation of syscalls.c for ARM compiler toolchains built
* without newlib. Allows usage of printf() and friends as well as heap
* allocation.
*
* NOTE: Platform/BSP must implement uart_read() and uart_write().
*
* NOTE: Platform/BSP linker script must define "end" and "heap_top" which are
* the heap base and top respectively.
*
* No file table is implemented. All file read/write operations are carried
* out on the UART driver, regardless of file descriptor.
*
* Mostly based on code from http://balau82.wordpress.com
*
*/
#include <sys/stat.h>
#include "uart.h"
/**
* Define all functions as weak so that the functions in this file will
* only be used if the compiler toolchain doesn't already provide them.
*/
extern int _close(int file) __attribute__((weak));
extern int _fstat(int file, struct stat *st) __attribute__((weak));
extern int _isatty(int file) __attribute__((weak));
extern int _lseek(int file, int ptr, int dir) __attribute__((weak));
extern int _open(const char *name, int flags, int mode) __attribute__((weak));
extern int _read(int file, char *ptr, int len) __attribute__((weak));
extern caddr_t _sbrk(int incr) __attribute__((weak));
extern int _write(int file, char *ptr, int len) __attribute__((weak));
/**
* \b _close
*
* Simple stub implementation with no file table. All parameters ignored.
*
*/
int _close(int file)
{
return -1;
}
/**
* \b _fstat
*
* Simple stub implementation. Always return character device.
*
*/
int _fstat(int file, struct stat *st)
{
/* Only UART supported, always return character-oriented device file */
st->st_mode = S_IFCHR;
return 0;
}
/**
* \b _isatty
*
* Simple stub implementation. Only UART supported so TTY always true.
*
*/
int _isatty(int file)
{
return 1;
}
/**
* \b _lseek
*
* Simple stub implementation. All parameters ignored.
*
*/
int _lseek(int file, int ptr, int dir)
{
return 0;
}
/**
* \b _open
*
* Simple stub implementation with no file table. All parameters ignored.
*
*/
int _open(const char *name, int flags, int mode)
{
return -1;
}
/**
* \b _read
*
* Simple read file implementation. Ignores file descriptor parameter
* and always reads from the UART driver.
*
* @param[in] file File descriptor (parameter ignored)
* @param[in] ptr Pointer to receive buffer
* @param[in] len Max bytes to read
*
* @retval Number of bytes read
*/
int _read(int file, char *ptr, int len)
{
/* Read from the UART driver, regardless of file descriptor */
return (uart_read (ptr, len));
}
/**
* \b _write
*
* Simple write file implementation. Ignores file descriptor parameter
* and always writes to the UART driver.
*
* @param[in] file File descriptor (parameter ignored)
* @param[in] ptr Pointer to write buffer
* @param[in] len Number of bytes to write
*
* @retval Number of bytes written
*/
int _write(int file, char *ptr, int len)
{
/* Write to the UART driver, regardless of file descriptor */
return (uart_write (ptr, len));
}
/**
* \b _sbrk
*
* Simple heap implementation.
*
* The platform/BSP must define "end" and "heap_top" which are the heap
* base and top respectively.
*
* @param[in] incr Chunk size
*
* @retval Pointer to allocated chunk start
*/
caddr_t _sbrk(int incr)
{
extern char end; /* Defined by the linker */
extern char heap_top; /* Defined by the linker */
static char *heap_end = 0;
char *prev_heap_end;
/* First time in, initialise heap base using definition from linker script */
if (heap_end == 0)
{
heap_end = &end;
}
/* Save the previous heap base */
prev_heap_end = heap_end;
/* Check we have not passed the heap top */
if (heap_end + incr > &heap_top)
{
/* Heap top reached, failed to allocate */
return (caddr_t)0;
}
/* New heap base */
heap_end += incr;
/* Return pointer to previous base (where our allocation starts) */
return (caddr_t)prev_heap_end;
}

203
ports/arm/tests-main.c Normal file
View File

@@ -0,0 +1,203 @@
/*
* Copyright (c) 2013, Kelvin Lawson. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. No personal names or organizations' names associated with the
* Atomthreads project may be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE ATOMTHREADS PROJECT AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
* TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
* PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE PROJECT OR CONTRIBUTORS 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.
*/
#include <stdio.h>
#include "atom.h"
#include "atomport-private.h"
#include "atomtests.h"
#include "atomtimer.h"
/* Constants */
/*
* Idle thread stack size
*
* This needs to be large enough to handle any interrupt handlers
* and callbacks called by interrupt handlers (e.g. user-created
* timer callbacks) as well as the saving of all context when
* switching away from this thread.
*/
#define IDLE_STACK_SIZE_BYTES 512
/*
* Main thread stack size
*
* Note that this is not a required OS kernel thread - you will replace
* this with your own application thread.
*
* In this case the Main thread is responsible for calling out to the
* test routines. Once a test routine has finished, the test status is
* printed out on the UART and the thread remains running in a loop.
*
* The Main thread stack generally needs to be larger than the idle
* thread stack, as not only does it need to store interrupt handler
* stack saves and context switch saves, but the application main thread
* will generally be carrying out more nested function calls and require
* stack for application code local variables etc.
*
* 1KB might be adequate but if using printf() then at least 2KB would be
* prudent otherwise the stdio functions otherwise stack overruns are
* likely. Nearly 2KB was seen to be used on the toolchain used for
* development.
*/
#define MAIN_STACK_SIZE_BYTES 4096
/* Local data */
/* Application threads' TCBs */
static ATOM_TCB main_tcb;
/* Main thread's stack area */
static uint8_t main_thread_stack[MAIN_STACK_SIZE_BYTES];
/* Idle thread's stack area */
static uint8_t idle_thread_stack[IDLE_STACK_SIZE_BYTES];
/* Forward declarations */
static void main_thread_func (uint32_t data);
/**
* \b main
*
* Program entry point.
*
* Creates an application thread and starts the OS.
*/
int main ( void )
{
int8_t status;
/**
* Note: to protect OS structures and data during initialisation,
* interrupts must remain disabled until the first thread
* has been restored. They are reenabled at the very end of
* the first thread restore, at which point it is safe for a
* reschedule to take place.
*/
/**
* Initialise the OS before creating our threads.
*/
status = atomOSInit(&idle_thread_stack[0], IDLE_STACK_SIZE_BYTES, TRUE);
if (status == ATOM_OK)
{
/* Create an application thread */
status = atomThreadCreate(&main_tcb,
TEST_THREAD_PRIO, main_thread_func, 0,
&main_thread_stack[0],
MAIN_STACK_SIZE_BYTES,
TRUE);
if (status == ATOM_OK)
{
/**
* First application thread successfully created. It is
* now possible to start the OS. Execution will not return
* from atomOSStart(), which will restore the context of
* our application thread and start executing it.
*
* Note that interrupts are still disabled at this point.
* They will be enabled as we restore and execute our first
* thread in archFirstThreadRestore().
*/
atomOSStart();
}
}
while (1)
;
/* There was an error starting the OS if we reach here */
return (0);
}
/**
* \b main_thread_func
*
* Entry point for main application thread.
*
* This is the first thread that will be executed when the OS is started.
*
* @param[in] data Unused (optional thread entry parameter)
*
* @return None
*/
static void main_thread_func (uint32_t data)
{
uint32_t test_status;
/* Put a message out on the UART */
printf ("Go\n");
/* Start test. All tests use the same start API. */
test_status = test_start();
/* Check main thread stack usage (if enabled) */
#ifdef ATOM_STACK_CHECKING
if (test_status == 0)
{
uint32_t used_bytes, free_bytes;
/* Check idle thread stack usage */
if (atomThreadStackCheck (&main_tcb, &used_bytes, &free_bytes) == ATOM_OK)
{
/* Check the thread did not use up to the end of stack */
if (free_bytes == 0)
{
printf ("Main stack overflow\n");
test_status++;
}
/* Log the stack usage */
#ifdef TESTS_LOG_STACK_USAGE
printf ("MainUse:%d\n", (int)used_bytes);
#endif
}
}
#endif
/* Log final status */
if (test_status == 0)
{
printf ("Pass\n");
}
else
{
printf ("Fail(%d)\n", (int)test_status);
}
}

View File

@@ -27,7 +27,7 @@ architecture-specific details such as appropriate types for 8-bit, 16-bit
etc variables, the port's system tick frequency, and macros for performing
interrupt lockouts / critical sections:
* atomuser.h: Port-specific header required by the kernel for each port
* atomport.h: Port-specific header required by the kernel for each port
A couple of additional source files are also included here:

View File

@@ -148,7 +148,7 @@ archContextSwitch:
mov r28,r24 /* Move old_tcb_ptr param into the Y-regs so we */
mov r29,r25 /* can access the TCB via a pointer. */
st Y,r16 /* Store SPH/SPL to old_tcb_ptr->tcb_save_ptr which */
st Y,r16 /* Store SPH/SPL to old_tcb_ptr->sp_save_ptr which */
std Y+1,r17 /* is conveniently the first member of the TCB. */

View File

@@ -45,6 +45,8 @@
#endif
/* Local data */
/*
* Semaphore for single-threaded access to UART device
*/

View File

@@ -28,7 +28,7 @@ architecture-specific details such as appropriate types for 8-bit, 16-bit
etc variables, the port's system tick frequency, and macros for performing
interrupt lockouts / critical sections:
* atomuser.h: Port-specific header required by the kernel for each port
* atomport.h: Port-specific header required by the kernel for each port
A few additional source files are also included here:

View File

@@ -28,7 +28,7 @@ architecture-specific details such as appropriate types for 8-bit, 16-bit
etc variables, the port's system tick frequency, and macros for performing
interrupt lockouts / critical sections:
* atomuser.h: Port-specific header required by the kernel for each port
* atomport.h: Port-specific header required by the kernel for each port
A few additional source files are also included here:

View File

@@ -28,7 +28,7 @@ architecture-specific details such as appropriate types for 8-bit, 16-bit
etc variables, the port's system tick frequency, and macros for performing
interrupt lockouts / critical sections:
* atomuser.h: Port-specific header required by the kernel for each port
* atomport.h: Port-specific header required by the kernel for each port
A few additional source files are also included here: