summaryrefslogtreecommitdiffstats
path: root/zpu/sw/freertos
diff options
context:
space:
mode:
authorBert Lange <b.lange@hzdr.de>2015-04-15 13:36:55 +0200
committerBert Lange <b.lange@hzdr.de>2015-04-15 13:36:55 +0200
commita1c964908b51599bf624bd2d253419c7e629f195 (patch)
tree06125d59e83b7dde82d1bb57bc0e09ca83451b98 /zpu/sw/freertos
parentbbfe29a15f11548eb7c9fa71dcb4d2d18c164a53 (diff)
parent8679e4f91dcae05aef40f96629f33f0f4161f14a (diff)
downloadzpu-a1c964908b51599bf624bd2d253419c7e629f195.zip
zpu-a1c964908b51599bf624bd2d253419c7e629f195.tar.gz
Merge branch 'master' of https://github.com/zylin/zpu
Diffstat (limited to 'zpu/sw/freertos')
-rw-r--r--zpu/sw/freertos/port/port.c271
-rw-r--r--zpu/sw/freertos/port/portasm.s142
-rw-r--r--zpu/sw/freertos/port/portmacro.h125
-rw-r--r--zpu/sw/freertos/readme.txt40
-rw-r--r--zpu/sw/freertos/sample/FreeRTOSConfig.h96
-rw-r--r--zpu/sw/freertos/sample/Makefile50
-rw-r--r--zpu/sw/freertos/sample/test1.c67
7 files changed, 791 insertions, 0 deletions
diff --git a/zpu/sw/freertos/port/port.c b/zpu/sw/freertos/port/port.c
new file mode 100644
index 0000000..ff243ee
--- /dev/null
+++ b/zpu/sw/freertos/port/port.c
@@ -0,0 +1,271 @@
+/*
+ FreeRTOS.org V5.3.0 - Copyright (C) 2003-2009 Richard Barry.
+
+ This file is part of the FreeRTOS.org distribution.
+
+ FreeRTOS.org 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.org without being obliged to provide
+ the source code for any proprietary components. Alternative commercial
+ license and support terms are also available upon request. See the
+ licensing section of http://www.FreeRTOS.org for full details.
+
+ FreeRTOS.org 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.org; if not, write to the Free Software Foundation, Inc., 59
+ Temple Place, Suite 330, Boston, MA 02111-1307 USA.
+
+
+ ***************************************************************************
+ * *
+ * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation *
+ * *
+ * This is a concise, step by step, 'hands on' guide that describes both *
+ * general multitasking concepts and FreeRTOS specifics. It presents and *
+ * explains numerous examples that are written using the FreeRTOS API. *
+ * Full source code for all the examples is provided in an accompanying *
+ * .zip file. *
+ * *
+ ***************************************************************************
+
+ 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.
+*/
+
+/*-----------------------------------------------------------
+ * Implementation of functions defined in portable.h for the MicroBlaze port.
+ *----------------------------------------------------------*/
+
+
+/* Scheduler includes. */
+#include "FreeRTOS.h"
+#include "task.h"
+
+/* Standard includes. */
+#include <string.h>
+
+/* hardware/software platform specific defines */
+#define DISABLE_C_PROTOTYPES
+#include <devices.h>
+
+/* Tasks are started with interrupts enabled. */
+#define portINITIAL_INTERRUPT_ENABLE ( ( portSTACK_TYPE ) INTERRUPT_GLOBAL_ENABLE )
+
+/* Tasks are started with a critical section nesting of 0 - however prior
+to the scheduler being commenced we don't want the critical nesting level
+to reach zero, so it is initialised to a high value. */
+#define portINITIAL_NESTING_VALUE ( 0xff )
+
+/* The stack used by the ISR is filled with a known value to assist in
+debugging. */
+#define portISR_STACK_FILL_VALUE 0x55555555
+
+/* Counts the nesting depth of calls to portENTER_CRITICAL(). Each task
+maintains it's own count, so this variable is saved as part of the task
+context. */
+volatile unsigned portBASE_TYPE uxCriticalNesting = portINITIAL_NESTING_VALUE;
+
+/* To limit the amount of stack required by each task, this port uses a
+separate stack for interrupts. */
+unsigned portLONG *pulISRStack;
+
+/*-----------------------------------------------------------*/
+
+/*
+ * Sets up the periodic ISR used for the RTOS tick. This uses timer 0, but
+ * could have alternatively used the watchdog timer or timer 1.
+ */
+static void prvSetupTimerInterrupt( void );
+/*-----------------------------------------------------------*/
+
+/*
+ * Initialise the stack of a task to look exactly as if a call to
+ * portSAVE_CONTEXT had been made.
+ *
+ * See the header file portable.h.
+ */
+portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters )
+{
+ /* Function call parameters. */
+ pxTopOfStack--;
+ *pxTopOfStack = ( portSTACK_TYPE ) pvParameters;
+
+ /* Place initial PC (task entry point) */
+ pxTopOfStack--;
+ *pxTopOfStack = ( portSTACK_TYPE ) pxCode; /* PC */
+
+ /* Place initial value for INTERRUPT global ENABLE */
+ pxTopOfStack--;
+ *pxTopOfStack = portINITIAL_INTERRUPT_ENABLE; /* interrupt state (global enable) */
+
+ /* Stack an initial value for the critical section nesting. This
+ is initialised to zero as tasks are started with interrupts enabled. */
+ pxTopOfStack--;
+ *pxTopOfStack = ( portSTACK_TYPE ) 0x00;
+
+ /* Place an initial value for all temporary registers mapped to mem[0..16] by gcc */
+ pxTopOfStack--;
+ *pxTopOfStack = ( portSTACK_TYPE ) 0x11111111; /* mem[0] */
+ pxTopOfStack--;
+ *pxTopOfStack = ( portSTACK_TYPE ) 0x22222222; /* mem[4] */
+ pxTopOfStack--;
+ *pxTopOfStack = ( portSTACK_TYPE ) 0x33333333; /* mem[8] */
+ pxTopOfStack--;
+ *pxTopOfStack = ( portSTACK_TYPE ) 0x44444444; /* mem[12] */
+
+ /* Return a pointer to the top of the stack we have generated so this can
+ be stored in the task control block for the task. */
+ return pxTopOfStack;
+}
+/*-----------------------------------------------------------*/
+
+portBASE_TYPE xPortStartScheduler( void )
+{
+extern void ( __FreeRTOS_interrupt_handler )( void );
+extern void ( vStartFirstTask )( void );
+
+ /* Setup the FreeRTOS interrupt handler */
+ *(volatile unsigned *) INTERRUPT_VECTOR = (unsigned) __FreeRTOS_interrupt_handler;
+
+ /* Setup the hardware to generate the tick. Interrupts are disabled when
+ this function is called. */
+ prvSetupTimerInterrupt();
+
+ /* Allocate the stack to be used by the interrupt handler. */
+ pulISRStack = ( unsigned portLONG * ) pvPortMalloc( configMINIMAL_STACK_SIZE * sizeof( portSTACK_TYPE ) );
+
+ /* Restore the context of the first task that is going to run. */
+ if( pulISRStack != NULL )
+ {
+ /* Fill the ISR stack with a known value to facilitate debugging. */
+ memset( pulISRStack, portISR_STACK_FILL_VALUE, configMINIMAL_STACK_SIZE * sizeof( portSTACK_TYPE ) );
+ pulISRStack += ( configMINIMAL_STACK_SIZE - 1 );
+
+ /* Kick off the first task. */
+ vStartFirstTask();
+ }
+
+ /* Should not get here as the tasks are now running! */
+ return pdFALSE;
+}
+/*-----------------------------------------------------------*/
+
+void vPortEndScheduler( void )
+{
+ /* Not implemented. */
+}
+/*-----------------------------------------------------------*/
+
+/*
+ * Manual context switch called by portYIELD or taskYIELD.
+ */
+void vPortYield( void )
+{
+extern void VPortYieldASM( void );
+
+ /* Perform the context switch in a critical section to assure it is
+ not interrupted by the tick ISR. It is not a problem to do this as
+ each task maintains it's own interrupt status. */
+ portENTER_CRITICAL();
+ /* Jump directly to the yield function to ensure there is no
+ compiler generated prologue code. */
+ asm volatile ( "im VPortYieldASM \n\t" \
+ "call \n\t" );
+ portEXIT_CRITICAL();
+}
+/*-----------------------------------------------------------*/
+
+/*
+ * Hardware initialisation to generate the RTOS tick.
+ */
+static void prvSetupTimerInterrupt( void )
+{
+const unsigned portLONG ulCounterValue = configCPU_CLOCK_HZ / configTICK_RATE_HZ;
+
+ /* Initialize and start timer1 counter */
+ *(volatile unsigned *) TIMER1_PORT = ulCounterValue;
+ *(volatile unsigned *) TIMERS_CONTROL = TIMER1_ENABLE;
+
+ /* Enable timer1 interrupt while maintaining other bit states
+ but disable global enable */
+ *(volatile unsigned *) INTERRUPT_ENABLE &= ~INTERRUPT_GLOBAL_ENABLE;
+ *(volatile unsigned *) INTERRUPT_ENABLE |= INTERRUPT_TIMER1;
+}
+/*-----------------------------------------------------------*/
+
+/*
+ * The interrupt handler placed in the interrupt vector when the scheduler is
+ * started. The task context has already been saved when this is called.
+ * This handler determines the interrupt source and calls the relevant
+ * peripheral handler.
+ */
+void vTaskISRHandler( void )
+{
+void vTickISR(void);
+
+ unsigned int_status = *(volatile unsigned *) INTERRUPT_STATUS;
+ if(int_status & INTERRUPT_TIMER1) vTickISR();
+}
+/*-----------------------------------------------------------*/
+
+/*
+ * Handler for the timer interrupt.
+ */
+void vTickISR( void )
+{
+ /* Increment the RTOS tick - this might cause a task to unblock. */
+ vTaskIncrementTick();
+
+ /* Clear the timer interrupt */
+ /* ... in this platform, timer interrupt is cleared automatically */
+
+ /* If we are using the preemptive scheduler then we also need to determine
+ if this tick should cause a context switch. */
+ #if configUSE_PREEMPTION == 1
+ vTaskSwitchContext();
+ #endif
+}
+/*-----------------------------------------------------------*/
+
+void zpu_disable_interrupts(void)
+{
+ *(volatile unsigned *) INTERRUPT_ENABLE &= ~INTERRUPT_GLOBAL_ENABLE;
+}
+
+void zpu_enable_interrupts(void)
+{
+ *(volatile unsigned *) INTERRUPT_ENABLE |= INTERRUPT_GLOBAL_ENABLE;
+}
+
+/*-----------------------------------------------------------*/
+
+void zpu_enter_critical(void)
+{
+ portDISABLE_INTERRUPTS();
+ uxCriticalNesting++;
+}
+
+void zpu_exit_critical(void)
+{
+ if( --uxCriticalNesting == 0 )
+ {
+ portENABLE_INTERRUPTS();
+ }
+}
diff --git a/zpu/sw/freertos/port/portasm.s b/zpu/sw/freertos/port/portasm.s
new file mode 100644
index 0000000..29c41ab
--- /dev/null
+++ b/zpu/sw/freertos/port/portasm.s
@@ -0,0 +1,142 @@
+ .extern pxCurrentTCB
+ .extern vTaskISRHandler
+ .extern vTaskSwitchContext
+ .extern uxCriticalNesting
+ .extern pulISRStack
+
+ .global __FreeRTOS_interrupt_handler
+ .global VPortYieldASM
+ .global vStartFirstTask
+
+/* interrupt controller port */
+ .equ INTERRUPT_ENABLE,0x8020
+
+.macro portSAVE_CONTEXT
+ /* PC is at the top of stack */
+
+ /* store interrupt global enable bit */
+ im INTERRUPT_ENABLE
+ load
+ im 1
+ and
+
+ /* Store nesting critical level */
+ im uxCriticalNesting
+ load
+
+ /* Store temporary registers */
+ im 0
+ load /* store mem[0] */
+ im 4
+ load /* store mem[4] */
+ im 8
+ load /* store mem[8] */
+ im 12
+ load /* store mem[12] */
+
+ /* Store top of stack at pxCurrentTCB */
+ pushsp
+ im pxCurrentTCB
+ load
+ store
+.endm
+
+.macro portRESTORE_CONTEXT
+ im pxCurrentTCB /* Load the top of stack value from the TCB. */
+ load
+ load
+ popsp
+
+ /* Restore the temporary registers. */
+ im 12
+ store /* restore mem[12] */
+ im 8
+ store /* restore mem[8] */
+ im 4
+ store /* restore mem[4] */
+ im 0
+ store /* restore mem[0] */
+
+ /* Load the critical nesting value. */
+ im uxCriticalNesting
+ store
+
+ /* Set interrupt global enable status */
+ im INTERRUPT_ENABLE
+ load
+ im ~1
+ and
+ or
+ im INTERRUPT_ENABLE
+ store
+
+ /* restore PC and enable interrupts at ZPU level */
+ .byte 0x03 /* popint */
+.endm
+
+.macro portRESTORE_CONTEXT_NOINTERRUPT
+ im pxCurrentTCB /* Load the top of stack value from the TCB. */
+ load
+ load
+ popsp
+
+ /* Restore the temporary registers. */
+ im 12
+ store /* restore mem[12] */
+ im 8
+ store /* restore mem[8] */
+ im 4
+ store /* restore mem[4] */
+ im 0
+ store /* restore mem[0] */
+
+ /* Load the critical nesting value. */
+ im uxCriticalNesting
+ store
+
+ /* Set interrupt global enable status */
+ im INTERRUPT_ENABLE
+ load
+ im ~1
+ and
+ or
+ im INTERRUPT_ENABLE
+ store
+
+ /* restore PC */
+ poppc
+.endm
+
+ .text
+ .align 2
+
+__FreeRTOS_interrupt_handler:
+ portSAVE_CONTEXT
+
+ /* Now switch to use the ISR stack. */
+ im pulISRStack
+ load
+ popsp
+
+ /* Call function */
+ im vTaskISRHandler
+ call
+
+ portRESTORE_CONTEXT
+
+VPortYieldASM:
+ portSAVE_CONTEXT
+
+ /* Now switch to use the ISR stack. */
+ im pulISRStack
+ load
+ popsp
+
+ /* Call function to switch context */
+ im vTaskSwitchContext
+ call
+
+ portRESTORE_CONTEXT_NOINTERRUPT
+
+vStartFirstTask:
+ portRESTORE_CONTEXT_NOINTERRUPT
diff --git a/zpu/sw/freertos/port/portmacro.h b/zpu/sw/freertos/port/portmacro.h
new file mode 100644
index 0000000..2b4d35a
--- /dev/null
+++ b/zpu/sw/freertos/port/portmacro.h
@@ -0,0 +1,125 @@
+/*
+ FreeRTOS.org V5.3.0 - Copyright (C) 2003-2009 Richard Barry.
+
+ This file is part of the FreeRTOS.org distribution.
+
+ FreeRTOS.org 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.org without being obliged to provide
+ the source code for any proprietary components. Alternative commercial
+ license and support terms are also available upon request. See the
+ licensing section of http://www.FreeRTOS.org for full details.
+
+ FreeRTOS.org 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.org; if not, write to the Free Software Foundation, Inc., 59
+ Temple Place, Suite 330, Boston, MA 02111-1307 USA.
+
+
+ ***************************************************************************
+ * *
+ * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation *
+ * *
+ * This is a concise, step by step, 'hands on' guide that describes both *
+ * general multitasking concepts and FreeRTOS specifics. It presents and *
+ * explains numerous examples that are written using the FreeRTOS API. *
+ * Full source code for all the examples is provided in an accompanying *
+ * .zip file. *
+ * *
+ ***************************************************************************
+
+ 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 PORTMACRO_H
+#define PORTMACRO_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/*-----------------------------------------------------------
+ * Port specific definitions.
+ *
+ * The settings in this file configure FreeRTOS correctly for the
+ * given hardware and compiler.
+ *
+ * These settings should not be altered.
+ *-----------------------------------------------------------
+ */
+
+/* Type definitions. */
+#define portCHAR char
+#define portFLOAT float
+#define portDOUBLE double
+#define portLONG long
+#define portSHORT short
+#define portSTACK_TYPE unsigned portLONG
+#define portBASE_TYPE portLONG
+
+#if( configUSE_16_BIT_TICKS == 1 )
+ typedef unsigned portSHORT portTickType;
+ #define portMAX_DELAY ( portTickType ) 0xffff
+#else
+ typedef unsigned portLONG portTickType;
+ #define portMAX_DELAY ( portTickType ) 0xffffffff
+#endif
+/*-----------------------------------------------------------*/
+
+/* Interrupt control macros. */
+void zpu_disable_interrupts(void);
+void zpu_enable_interrupts(void);
+#define portDISABLE_INTERRUPTS() zpu_disable_interrupts()
+#define portENABLE_INTERRUPTS() zpu_enable_interrupts()
+/*-----------------------------------------------------------*/
+
+/* Critical section macros. */
+void zpu_enter_critical(void);
+void zpu_exit_critical(void);
+#define portENTER_CRITICAL() zpu_enter_critical()
+#define portEXIT_CRITICAL() zpu_exit_critical()
+/*-----------------------------------------------------------*/
+
+/* Task utilities. */
+void vPortYield( void );
+#define portYIELD() vPortYield()
+
+void vTaskSwitchContext();
+#define portYIELD_FROM_ISR() vTaskSwitchContext()
+/*-----------------------------------------------------------*/
+
+/* Hardware specifics. */
+#define portBYTE_ALIGNMENT 4
+#define portSTACK_GROWTH ( -1 )
+#define portTICK_RATE_MS ( ( portTickType ) 1000 / configTICK_RATE_HZ )
+#define portNOP() asm volatile ( "nop\n" )
+/*-----------------------------------------------------------*/
+
+/* Task function macros as described on the FreeRTOS.org WEB site. */
+#define portTASK_FUNCTION_PROTO( vFunction, pvParameters ) void vFunction( void *pvParameters )
+#define portTASK_FUNCTION( vFunction, pvParameters ) void vFunction( void *pvParameters )
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* PORTMACRO_H */
+
diff --git a/zpu/sw/freertos/readme.txt b/zpu/sw/freertos/readme.txt
new file mode 100644
index 0000000..a1f1c89
--- /dev/null
+++ b/zpu/sw/freertos/readme.txt
@@ -0,0 +1,40 @@
+The FreeRTOS port was contributed by
+Antonio Anton <antonio.anton@anro-ingenieros.com>.
+
+Some of the files state that someone else is copyright
+holder, but I believe that to be copy and paste laziness
+and that, in fact, Antonio did this port.
+
+The port needs work, but is committed to ZPU git repository
+to get things started.
+
+Post questions to the zylin-zpu mailing list.
+
+Øyvind Harboe
+14/9-2009
+
+From Antonio:
+
+Ported version: 5.3.0
+Port goes to folder ${FREERTOS_ROOT}/Source/portable/GCC/ZPU
+
+portmacro.h : macro definitions for this port
+portasm.s : contains code for context switch, interrupt handler and
+other initializations
+port.c : other initialization functions that not need to be
+assembly code.
+
+(please note that #include <device.h> in port.c is specific for my ZPU
+port; it contains the definitions my peripherals)
+
+Each FreeRTOS application is compiled with the FreeRTOS port itself
+(source code).
+
+2nd file contains a sample application which includes the Makefile in
+order to compile & link against FreeRTOS port. It will link against some
+specific library (-lio) and specific linker file (sram-zpu.ld) which are
+not included. You must adapt these to your peripheral and memory
+configuration.
+
+At the moment there is no documentation but the source code is quite
+commented.
diff --git a/zpu/sw/freertos/sample/FreeRTOSConfig.h b/zpu/sw/freertos/sample/FreeRTOSConfig.h
new file mode 100644
index 0000000..d9470fd
--- /dev/null
+++ b/zpu/sw/freertos/sample/FreeRTOSConfig.h
@@ -0,0 +1,96 @@
+/*
+ FreeRTOS.org V5.3.0 - Copyright (C) 2003-2009 Richard Barry.
+
+ This file is part of the FreeRTOS.org distribution.
+
+ FreeRTOS.org 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.org without being obliged to provide
+ the source code for any proprietary components. Alternative commercial
+ license and support terms are also available upon request. See the
+ licensing section of http://www.FreeRTOS.org for full details.
+
+ FreeRTOS.org 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.org; if not, write to the Free Software Foundation, Inc., 59
+ Temple Place, Suite 330, Boston, MA 02111-1307 USA.
+
+
+ ***************************************************************************
+ * *
+ * Get the FreeRTOS eBook! See http://www.FreeRTOS.org/Documentation *
+ * *
+ * This is a concise, step by step, 'hands on' guide that describes both *
+ * general multitasking concepts and FreeRTOS specifics. It presents and *
+ * explains numerous examples that are written using the FreeRTOS API. *
+ * Full source code for all the examples is provided in an accompanying *
+ * .zip file. *
+ * *
+ ***************************************************************************
+
+ 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 0
+#define configCPU_CLOCK_HZ ( ( unsigned portLONG ) 25000000 )
+#define configTICK_RATE_HZ ( ( portTickType ) 100 )
+#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 4 )
+#define configMINIMAL_STACK_SIZE ( ( unsigned portLONG ) 256 )
+#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 8 * 1024 ) )
+#define configMAX_TASK_NAME_LEN ( 5 )
+#define configUSE_TRACE_FACILITY 0
+#define configUSE_16_BIT_TICKS 0
+#define configIDLE_SHOULD_YIELD 1
+
+/* Co-routine definitions. */
+#define configUSE_CO_ROUTINES 0
+#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 0
+#define INCLUDE_vTaskCleanUpResources 0
+#define INCLUDE_vTaskSuspend 1
+#define INCLUDE_vTaskDelayUntil 1
+#define INCLUDE_vTaskDelay 1
+
+
+#endif /* FREERTOS_CONFIG_H */
diff --git a/zpu/sw/freertos/sample/Makefile b/zpu/sw/freertos/sample/Makefile
new file mode 100644
index 0000000..d3a6f6f
--- /dev/null
+++ b/zpu/sw/freertos/sample/Makefile
@@ -0,0 +1,50 @@
+PRJ = test1
+PATH_SW = /home/antonan/desarrollo/zpu/sw
+INCLUDES = $(PATH_SW)/freertos/Source/portable/GCC/ZPU/portmacro.h \
+ FreeRTOSConfig.h
+SRCS_C = $(PATH_SW)/freertos/Source/portable/GCC/ZPU/port.c \
+ $(PATH_SW)/freertos/Source/portable/MemMang/heap_1.c \
+ $(PATH_SW)/freertos/Source/croutine.c \
+ $(PATH_SW)/freertos/Source/list.c \
+ $(PATH_SW)/freertos/Source/queue.c \
+ $(PATH_SW)/freertos/Source/tasks.c \
+ test1.c
+SRCS_ASM = $(PATH_SW)/freertos/Source/portable/GCC/ZPU/portasm.s
+PATH_INC = -I$(PATH_SW)/include \
+ -I$(PATH_SW)/freertos/Source/include \
+ -I$(PATH_SW)/freertos/Source/portable/GCC/ZPU \
+ -I$(PATH_SW)/freertos/Demo/ZPU \
+ -I.
+OPTIONS = -g -Os -DGCC_ZPU
+LINK = -T $(PATH_SW)/ldscripts/zpu-sram.ld
+CRT = $(PATH_SW)/startup/crt-sram.o
+LLIB = -L $(PATH_SW)/lib
+LIBS = -lio -lgcc --start-group -lc -lbcc --end-group -lgcc -lio
+LFLAGS = --relax --gc-sections
+
+OBJS_ASM = $(SRCS_ASM:.s=.o)
+OBJS_C = $(SRCS_C:.c=.o)
+
+$(PRJ).srec: $(PRJ).out
+ zpu-elf-objcopy -O srec $(PRJ).out $(PRJ).srec
+ zpu-elf-objcopy -O binary $(PRJ).out $(PRJ).bin
+ bin2rom $(PRJ).bin $(PRJ).rom
+
+$(OBJS_ASM): $(SRCS_ASM)
+ zpu-elf-gcc $(OPTIONS) $(PATH_INC) -B. -c -Wa,-ahlms=$(@:.o=.lst) -o $@ $(@:.o=.s)
+
+$(OBJS_C): $(SRCS_C) $(INCLUDES)
+ zpu-elf-gcc $(OPTIONS) $(PATH_INC) -B. -c -Wa,-ahlms=$(@:.o=.lst) -o $@ $(@:.o=.c)
+
+$(PRJ).out: $(CRT) $(OBJS_C) $(OBJS_ASM)
+ zpu-elf-ld $(LLIB) $(LFLAGS) $(LINK) -Map=$(PRJ).map -o $(PRJ).out $(CRT) $(OBJS_C) $(OBJS_ASM) $(LIBS)
+
+
+clean:
+ -rm *.o
+ -rm *.out
+ -rm *.bin
+ -rm *.map
+ -rm *.lst
+ -rm *.srec
+ -rm *.rom
diff --git a/zpu/sw/freertos/sample/test1.c b/zpu/sw/freertos/sample/test1.c
new file mode 100644
index 0000000..41b4296
--- /dev/null
+++ b/zpu/sw/freertos/sample/test1.c
@@ -0,0 +1,67 @@
+/* Scheduler includes. */
+#include "FreeRTOS.h"
+#include "task.h"
+
+#include "devices.h"
+
+#define mainTINY_STACK 256
+void vTest(void *pvParameters);
+void vTest2(void *pvParameters);
+
+/*-----------------------------------------------------------*/
+
+/*
+ * Create all the demo tasks - then start the scheduler.
+ */
+int main (void)
+{
+ /* When re-starting a debug session (rather than cold booting) we want
+ to ensure the installed interrupt handlers do not execute until after the
+ scheduler has been started. */
+ portDISABLE_INTERRUPTS();
+
+ #if configUSE_PREEMPTION == 1
+ xTaskCreate( vTest, "TST1", mainTINY_STACK, ( void * ) 10, tskIDLE_PRIORITY, NULL );
+ xTaskCreate( vTest2, "TST2", mainTINY_STACK, ( void * ) 10, tskIDLE_PRIORITY, NULL );
+ #endif
+
+ /* Finally start the scheduler. */
+ vTaskStartScheduler();
+
+ /* Should not get here as the processor is now under control of the
+ scheduler! */
+
+ return 0;
+}
+
+void vTest(void *pvParameters)
+{
+const portTickType xDelay = 100 / portTICK_RATE_MS;
+ unsigned bit = 16;
+ unsigned dir = 0;
+
+ for(;;)
+ {
+ CLEAR_BIT(SP3SK_GPIO, bit);
+ if(dir == 0) { if(++bit == 23) { dir=1; } }
+ else { if(--bit == 16) { dir=0;} }
+ SET_BIT(SP3SK_GPIO, bit);
+ vTaskDelay( xDelay );
+ }
+}
+
+void vTest2(void *pvParameters)
+{
+const portTickType xDelay = 250 / portTICK_RATE_MS;
+ unsigned pos;
+ char marcas[] = "|/-\\";
+
+ for(;;)
+ {
+ uart1_printline("\r");
+ uart1_printline("Running...");
+ uart1_printchar(marcas[pos]);
+ if(++pos == 4) pos = 0;
+ vTaskDelay( xDelay );
+ }
+}
OpenPOWER on IntegriCloud