From a5b65b0066b63468f09e0d714079f4603fb84dae Mon Sep 17 00:00:00 2001
From: Richard Barry <ribarry@amazon.com>
Date: Fri, 24 Feb 2012 12:05:01 +0000
Subject: [PATCH] Added IAR port layer for the Cortex-M0.

---
 Source/portable/IAR/ARM_CM0/port.c      | 208 ++++++++++++++++++++++++
 Source/portable/IAR/ARM_CM0/portasm.s   | 155 ++++++++++++++++++
 Source/portable/IAR/ARM_CM0/portmacro.h | 131 +++++++++++++++
 3 files changed, 494 insertions(+)
 create mode 100644 Source/portable/IAR/ARM_CM0/port.c
 create mode 100644 Source/portable/IAR/ARM_CM0/portasm.s
 create mode 100644 Source/portable/IAR/ARM_CM0/portmacro.h

diff --git a/Source/portable/IAR/ARM_CM0/port.c b/Source/portable/IAR/ARM_CM0/port.c
new file mode 100644
index 0000000000..55665d7e0b
--- /dev/null
+++ b/Source/portable/IAR/ARM_CM0/port.c
@@ -0,0 +1,208 @@
+/*
+    FreeRTOS V7.1.0 - Copyright (C) 2011 Real Time Engineers Ltd.
+	
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS tutorial books are available in pdf and paperback.        *
+     *    Complete, revised, and edited pdf reference manuals are also       *
+     *    available.                                                         *
+     *                                                                       *
+     *    Purchasing FreeRTOS documentation will not only help you, by       *
+     *    ensuring you get running as quickly as possible and with an        *
+     *    in-depth knowledge of how to use FreeRTOS, it will also help       *
+     *    the FreeRTOS project to continue with its mission of providing     *
+     *    professional grade, cross platform, de facto standard solutions    *
+     *    for microcontrollers - completely free of charge!                  *
+     *                                                                       *
+     *    >>> See http://www.FreeRTOS.org/Documentation for details. <<<     *
+     *                                                                       *
+     *    Thank you for using FreeRTOS, and thank you for your support!      *
+     *                                                                       *
+    ***************************************************************************
+
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation AND MODIFIED BY the FreeRTOS exception.
+    >>>NOTE<<< The modification to the GPL is included to allow you to
+    distribute a combined work that includes FreeRTOS without being obliged to
+    provide the source code for proprietary components outside of the FreeRTOS
+    kernel.  FreeRTOS is distributed in the hope that it will be useful, but
+    WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
+    or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for
+    more details. You should have received a copy of the GNU General Public
+    License and the FreeRTOS license exception along with FreeRTOS; if not it
+    can be viewed here: http://www.freertos.org/a00114.html and also obtained
+    by writing to Richard Barry, contact details for whom are available on the
+    FreeRTOS WEB site.
+
+    1 tab == 4 spaces!
+
+    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 ARM CM0 port.
+ *----------------------------------------------------------*/
+
+/* Scheduler includes. */
+#include "FreeRTOS.h"
+#include "task.h"
+
+/* Constants required to manipulate the NVIC. */
+#define portNVIC_SYSTICK_CTRL		( ( volatile unsigned long *) 0xe000e010 )
+#define portNVIC_SYSTICK_LOAD		( ( volatile unsigned long *) 0xe000e014 )
+#define portNVIC_INT_CTRL			( ( volatile unsigned long *) 0xe000ed04 )
+#define portNVIC_SYSPRI2			( ( volatile unsigned long *) 0xe000ed20 )
+#define portNVIC_SYSTICK_CLK		0x00000004
+#define portNVIC_SYSTICK_INT		0x00000002
+#define portNVIC_SYSTICK_ENABLE		0x00000001
+#define portNVIC_PENDSVSET			0x10000000
+#define portMIN_INTERRUPT_PRIORITY	( 255UL )
+#define portNVIC_PENDSV_PRI			( portMIN_INTERRUPT_PRIORITY << 16UL )
+#define portNVIC_SYSTICK_PRI		( portMIN_INTERRUPT_PRIORITY << 24UL )
+
+/* Constants required to set up the initial stack. */
+#define portINITIAL_XPSR			( 0x01000000 )
+
+/* For backward compatibility, ensure configKERNEL_INTERRUPT_PRIORITY is
+defined.  The value 255 should also ensure backward compatibility.
+FreeRTOS.org versions prior to V4.3.0 did not include this definition. */
+#ifndef configKERNEL_INTERRUPT_PRIORITY
+	#define configKERNEL_INTERRUPT_PRIORITY 0
+#endif
+
+/* Each task maintains its own interrupt status in the critical nesting
+variable. */
+static unsigned portBASE_TYPE uxCriticalNesting = 0xaaaaaaaa;
+
+/*
+ * Setup the timer to generate the tick interrupts.
+ */
+static void prvSetupTimerInterrupt( void );
+
+/*
+ * Exception handlers.
+ */
+void xPortSysTickHandler( void );
+
+/*
+ * Start first task is a separate function so it can be tested in isolation.
+ */
+extern void vPortStartFirstTask( void );
+
+/*-----------------------------------------------------------*/
+
+/*
+ * See header file for description.
+ */
+portSTACK_TYPE *pxPortInitialiseStack( portSTACK_TYPE *pxTopOfStack, pdTASK_CODE pxCode, void *pvParameters )
+{
+	/* Simulate the stack frame as it would be created by a context switch
+	interrupt. */
+	pxTopOfStack--; /* Offset added to account for the way the MCU uses the stack on entry/exit of interrupts. */
+	*pxTopOfStack = portINITIAL_XPSR;	/* xPSR */
+	pxTopOfStack--;
+	*pxTopOfStack = ( portSTACK_TYPE ) pxCode;	/* PC */
+	pxTopOfStack -= 6;	/* LR, R12, R3..R1 */
+	*pxTopOfStack = ( portSTACK_TYPE ) pvParameters;	/* R0 */
+	pxTopOfStack -= 8; /* R11..R4. */
+
+	return pxTopOfStack;
+}
+/*-----------------------------------------------------------*/
+
+/*
+ * See header file for description.
+ */
+portBASE_TYPE xPortStartScheduler( void )
+{
+	/* Make PendSV and SysTick the lowest priority interrupts. */
+	*(portNVIC_SYSPRI2) |= portNVIC_PENDSV_PRI;
+	*(portNVIC_SYSPRI2) |= portNVIC_SYSTICK_PRI;
+
+	/* Start the timer that generates the tick ISR.  Interrupts are disabled
+	here already. */
+	prvSetupTimerInterrupt();
+	
+	/* Initialise the critical nesting count ready for the first task. */
+	uxCriticalNesting = 0;
+
+	/* Start the first task. */
+	vPortStartFirstTask();
+
+	/* Should not get here! */
+	return 0;
+}
+/*-----------------------------------------------------------*/
+
+void vPortEndScheduler( void )
+{
+	/* It is unlikely that the CM0 port will require this function as there
+	is nothing to return to.  */
+}
+/*-----------------------------------------------------------*/
+
+void vPortYieldFromISR( void )
+{
+	/* Set a PendSV to request a context switch. */
+	*(portNVIC_INT_CTRL) = portNVIC_PENDSVSET;
+}
+/*-----------------------------------------------------------*/
+
+void vPortEnterCritical( void )
+{
+	portDISABLE_INTERRUPTS();
+	uxCriticalNesting++;
+}
+/*-----------------------------------------------------------*/
+
+void vPortExitCritical( void )
+{
+	uxCriticalNesting--;
+	if( uxCriticalNesting == 0 )
+	{
+		portENABLE_INTERRUPTS();
+	}
+}
+/*-----------------------------------------------------------*/
+
+void xPortSysTickHandler( void )
+{
+unsigned long ulDummy;
+
+	/* If using preemption, also force a context switch. */
+	#if configUSE_PREEMPTION == 1
+		*(portNVIC_INT_CTRL) = portNVIC_PENDSVSET;	
+	#endif
+
+	ulDummy = portSET_INTERRUPT_MASK_FROM_ISR();
+	{
+		vTaskIncrementTick();
+	}
+	portCLEAR_INTERRUPT_MASK_FROM_ISR( ulDummy );
+}
+/*-----------------------------------------------------------*/
+
+/*
+ * Setup the systick timer to generate the tick interrupts at the required
+ * frequency.
+ */
+static void prvSetupTimerInterrupt( void )
+{
+	/* Configure SysTick to interrupt at the requested rate. */
+	*(portNVIC_SYSTICK_LOAD) = ( configCPU_CLOCK_HZ / configTICK_RATE_HZ ) - 1UL;
+	*(portNVIC_SYSTICK_CTRL) = portNVIC_SYSTICK_CLK | portNVIC_SYSTICK_INT | portNVIC_SYSTICK_ENABLE;
+}
+/*-----------------------------------------------------------*/
+
diff --git a/Source/portable/IAR/ARM_CM0/portasm.s b/Source/portable/IAR/ARM_CM0/portasm.s
new file mode 100644
index 0000000000..966d976206
--- /dev/null
+++ b/Source/portable/IAR/ARM_CM0/portasm.s
@@ -0,0 +1,155 @@
+/*
+    FreeRTOS V7.1.0 - Copyright (C) 2011 Real Time Engineers Ltd.
+	
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS tutorial books are available in pdf and paperback.        *
+     *    Complete, revised, and edited pdf reference manuals are also       *
+     *    available.                                                         *
+     *                                                                       *
+     *    Purchasing FreeRTOS documentation will not only help you, by       *
+     *    ensuring you get running as quickly as possible and with an        *
+     *    in-depth knowledge of how to use FreeRTOS, it will also help       *
+     *    the FreeRTOS project to continue with its mission of providing     *
+     *    professional grade, cross platform, de facto standard solutions    *
+     *    for microcontrollers - completely free of charge!                  *
+     *                                                                       *
+     *    >>> See http://www.FreeRTOS.org/Documentation for details. <<<     *
+     *                                                                       *
+     *    Thank you for using FreeRTOS, and thank you for your support!      *
+     *                                                                       *
+    ***************************************************************************
+
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation AND MODIFIED BY the FreeRTOS exception.
+    >>>NOTE<<< The modification to the GPL is included to allow you to
+    distribute a combined work that includes FreeRTOS without being obliged to
+    provide the source code for proprietary components outside of the FreeRTOS
+    kernel.  FreeRTOS is distributed in the hope that it will be useful, but
+    WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
+    or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for
+    more details. You should have received a copy of the GNU General Public
+    License and the FreeRTOS license exception along with FreeRTOS; if not it
+    can be viewed here: http://www.freertos.org/a00114.html and also obtained
+    by writing to Richard Barry, contact details for whom are available on the
+    FreeRTOS WEB site.
+
+    1 tab == 4 spaces!
+
+    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.
+*/
+
+#include <FreeRTOSConfig.h>
+
+/* For backward compatibility, ensure configKERNEL_INTERRUPT_PRIORITY is
+defined.  The value zero should also ensure backward compatibility.
+FreeRTOS.org versions prior to V4.3.0 did not include this definition. */
+#ifndef configKERNEL_INTERRUPT_PRIORITY
+	#define configKERNEL_INTERRUPT_PRIORITY 0
+#endif
+
+	
+	RSEG    CODE:CODE(2)
+	thumb
+
+	EXTERN vPortYieldFromISR
+	EXTERN pxCurrentTCB
+	EXTERN vTaskSwitchContext
+
+	PUBLIC vSetMSP
+	PUBLIC xPortPendSVHandler
+	PUBLIC vPortSVCHandler
+	PUBLIC vPortStartFirstTask
+
+
+/*-----------------------------------------------------------*/
+
+vSetMSP
+	msr msp, r0
+	bx lr
+	
+/*-----------------------------------------------------------*/
+
+xPortPendSVHandler:
+	mrs r0, psp							
+											
+	ldr	r3, =pxCurrentTCB	/* Get the location of the current TCB. */
+	ldr	r2, [r3]						
+											
+	subs r0, r0, #32		/* Make space for the remaining low registers. */
+	str r0, [r2]			/* Save the new top of stack. */
+	stmia r0!, {r4-r7}		/* Store the low registers that are not saved automatically. */
+	mov r4, r8				/* Store the high registers. */
+	mov r5, r9							
+	mov r6, r10							
+	mov r7, r11							
+	stmia r0!, {r4-r7}              	
+											
+	push {r3, r14}						
+	cpsid i								
+	bl vTaskSwitchContext				
+	cpsie i								
+	pop {r2, r3}			/* lr goes in r3. r2 now holds tcb pointer. */
+											
+	ldr r1, [r2]						
+	ldr r0, [r1]			/* The first item in pxCurrentTCB is the task top of stack. */
+	adds r0, r0, #16		/* Move to the high registers. */
+	ldmia r0!, {r4-r7}		/* Pop the high registers. */
+	mov r8, r4							
+	mov r9, r5							
+	mov r10, r6							
+	mov r11, r7							
+											
+	msr psp, r0				/* Remember the new top of stack for the task. */
+											
+	subs r0, r0, #32		/* Go back for the low registers that are not automatically restored. */
+	ldmia r0!, {r4-r7}		/* Pop low registers.  */
+											
+	bx r3								
+
+/*-----------------------------------------------------------*/
+
+vPortSVCHandler;
+	ldr	r3, =pxCurrentTCB	/* Restore the context. */
+	ldr r1, [r3]			/* Get the pxCurrentTCB address. */
+	ldr r0, [r1]			/* The first item in pxCurrentTCB is the task top of stack. */
+	adds r0, r0, #16		/* Move to the high registers. */
+	ldmia r0!, {r4-r7}		/* Pop the high registers. */
+	mov r8, r4						
+	mov r9, r5						
+	mov r10, r6						
+	mov r11, r7						
+										
+	msr psp, r0				/* Remember the new top of stack for the task. */
+										
+	subs r0, r0, #32		/* Go back for the low registers that are not automatically restored. */
+	ldmia r0!, {r4-r7}		/* Pop low registers.  */
+	mov r1, r14				/* OR R14 with 0x0d. */
+	movs r0, #0x0d					
+	orrs r1, r0						
+	bx r1							
+
+/*-----------------------------------------------------------*/
+
+vPortStartFirstTask
+	movs r0, #0x00 	 		/* Locate the top of stack. */
+	ldr r0, [r0] 		
+	msr msp, r0		 		/* Set the msp back to the start of the stack. */
+	cpsie i			 		/* Globally enable interrupts. */
+	svc 0			 		/* System call to start first task. */
+	nop				
+	
+	END
+	
\ No newline at end of file
diff --git a/Source/portable/IAR/ARM_CM0/portmacro.h b/Source/portable/IAR/ARM_CM0/portmacro.h
new file mode 100644
index 0000000000..806e99d2d2
--- /dev/null
+++ b/Source/portable/IAR/ARM_CM0/portmacro.h
@@ -0,0 +1,131 @@
+/*
+    FreeRTOS V7.1.0 - Copyright (C) 2011 Real Time Engineers Ltd.
+	
+
+    ***************************************************************************
+     *                                                                       *
+     *    FreeRTOS tutorial books are available in pdf and paperback.        *
+     *    Complete, revised, and edited pdf reference manuals are also       *
+     *    available.                                                         *
+     *                                                                       *
+     *    Purchasing FreeRTOS documentation will not only help you, by       *
+     *    ensuring you get running as quickly as possible and with an        *
+     *    in-depth knowledge of how to use FreeRTOS, it will also help       *
+     *    the FreeRTOS project to continue with its mission of providing     *
+     *    professional grade, cross platform, de facto standard solutions    *
+     *    for microcontrollers - completely free of charge!                  *
+     *                                                                       *
+     *    >>> See http://www.FreeRTOS.org/Documentation for details. <<<     *
+     *                                                                       *
+     *    Thank you for using FreeRTOS, and thank you for your support!      *
+     *                                                                       *
+    ***************************************************************************
+
+
+    This file is part of the FreeRTOS distribution.
+
+    FreeRTOS is free software; you can redistribute it and/or modify it under
+    the terms of the GNU General Public License (version 2) as published by the
+    Free Software Foundation AND MODIFIED BY the FreeRTOS exception.
+    >>>NOTE<<< The modification to the GPL is included to allow you to
+    distribute a combined work that includes FreeRTOS without being obliged to
+    provide the source code for proprietary components outside of the FreeRTOS
+    kernel.  FreeRTOS is distributed in the hope that it will be useful, but
+    WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
+    or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for
+    more details. You should have received a copy of the GNU General Public
+    License and the FreeRTOS license exception along with FreeRTOS; if not it
+    can be viewed here: http://www.freertos.org/a00114.html and also obtained
+    by writing to Richard Barry, contact details for whom are available on the
+    FreeRTOS WEB site.
+
+    1 tab == 4 spaces!
+
+    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	long
+
+#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
+/*-----------------------------------------------------------*/	
+
+/* Architecture specifics. */
+#define portSTACK_GROWTH			( -1 )
+#define portTICK_RATE_MS			( ( portTickType ) 1000 / configTICK_RATE_HZ )		
+#define portBYTE_ALIGNMENT			8
+/*-----------------------------------------------------------*/	
+
+
+/* Scheduler utilities. */
+extern void vPortYieldFromISR( void );
+
+#define portYIELD()					vPortYieldFromISR()
+
+#define portEND_SWITCHING_ISR( xSwitchRequired ) if( xSwitchRequired ) vPortYieldFromISR()
+/*-----------------------------------------------------------*/
+
+
+/* Critical section management. */
+
+extern void vPortEnterCritical( void );
+extern void vPortExitCritical( void );
+
+#define portDISABLE_INTERRUPTS()				__asm volatile( "cpsid i" )
+#define portENABLE_INTERRUPTS()					__asm volatile( "cpsie i" )
+#define portENTER_CRITICAL()					vPortEnterCritical()
+#define portEXIT_CRITICAL()						vPortExitCritical()
+#define portSET_INTERRUPT_MASK_FROM_ISR()		0;portDISABLE_INTERRUPTS()
+#define portCLEAR_INTERRUPT_MASK_FROM_ISR(x)	portENABLE_INTERRUPTS();(void)x
+
+/*-----------------------------------------------------------*/
+
+/* 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 )
+
+#define portNOP()
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* PORTMACRO_H */
+