diff --git a/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/FreeRTOSConfig.h b/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/FreeRTOSConfig.h
new file mode 100644
index 000000000..a514b469e
--- /dev/null
+++ b/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/FreeRTOSConfig.h
@@ -0,0 +1,83 @@
+/*
+ * FreeRTOS Kernel V10.4.1
+ * Copyright (C) 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy of
+ * this software and associated documentation files (the "Software"), to deal in
+ * the Software without restriction, including without limitation the rights to
+ * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
+ * the Software, and to permit persons to whom the Software is furnished to do so,
+ * subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in all
+ * copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
+ * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
+ * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
+ * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
+ *
+ * http://www.FreeRTOS.org
+ * http://aws.amazon.com/freertos
+ *
+ * 1 tab == 4 spaces!
+ */
+
+#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 long ) 20000000 )
+#define configTICK_RATE_HZ ( ( TickType_t ) 1000 )
+#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 70 )
+#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 7000 ) )
+#define configMAX_TASK_NAME_LEN ( 10 )
+#define configUSE_TRACE_FACILITY 0
+//#define configCHECK_FOR_STACK_OVERFLOW 0
+#define configUSE_16_BIT_TICKS 0
+#define configIDLE_SHOULD_YIELD 0
+#define configUSE_CO_ROUTINES 0
+
+#define configMAX_PRIORITIES ( 5 )
+#define configMAX_CO_ROUTINE_PRIORITIES ( 2 )
+
+/* Set the following definitions to 1 to include the API function, or zero
+to exclude the API function. */
+
+#define configUSE_MALLOC_FAILED_HOOK 1
+#define configUSE_MUTEXES 1
+#define configUSE_RECURSIVE_MUTEXES 1
+#define INCLUDE_vTaskPrioritySet 0
+#define INCLUDE_uxTaskPriorityGet 0
+#define INCLUDE_vTaskDelete 0
+#define INCLUDE_vTaskCleanUpResources 0
+#define INCLUDE_vTaskSuspend 0
+#define INCLUDE_vTaskDelayUntil 1
+#define INCLUDE_vTaskDelay 1
+//#define INCLUDE_uxTaskGetStackHighWaterMark 0
+//#define INCLUDE_uxTaskGetStackHighWaterMark2 0
+
+#define configKERNEL_INTERRUPT_PRIORITY 255
+/* !!!! configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to zero !!!!
+See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. */
+#define configMAX_SYSCALL_INTERRUPT_PRIORITY 191 /* equivalent to 0xa0, or priority 5. */
+
+
+
+#endif /* FREERTOS_CONFIG_H */
diff --git a/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/Makefile b/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/Makefile
new file mode 100644
index 000000000..40eafd9d3
--- /dev/null
+++ b/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/Makefile
@@ -0,0 +1,60 @@
+CC = arm-none-eabi-gcc
+BIN := RTOSDemo.axf
+
+BUILD_DIR := build
+
+FREERTOS_DIR_REL := ../../../FreeRTOS
+FREERTOS_DIR := $(abspath $(FREERTOS_DIR_REL))
+KERNEL_DIR := $(FREERTOS_DIR)/Source
+
+FREERTOS_PLUS_DIR_REL := ../../../FreeRTOS-Plus
+FREERTOS_PLUS_DIR := $(abspath $(FREERTOS_PLUS_DIR_REL))
+
+
+SOURCE_FILES := main.c init/startup.c main_blinky.c syscall.c
+SOURCE_FILES += $(KERNEL_DIR)/portable/GCC/ARM_CM3/port.c
+SOURCE_FILES += $(KERNEL_DIR)/tasks.c
+SOURCE_FILES += $(KERNEL_DIR)/list.c
+SOURCE_FILES += $(KERNEL_DIR)/queue.c
+SOURCE_FILES += ${KERNEL_DIR}/portable/MemMang/heap_1.c
+
+OBJ_FILES := $(SOURCE_FILES:%.c=$(BUILD_DIR)/%.o)
+
+DEFINES := -DprojCOVERAGE_TEST -DQEMU_SOC_MPS2
+
+LDFLAGS = -T ./scripts/mps2_m3.ld
+
+CFLAGS = -nostartfiles -mthumb -mcpu=cortex-m3
+CFLAGS += -Wno-builtin-declaration-mismatch -Werror
+
+ifeq ($(DEBUG), 1)
+ CFLAGS += -ggdb -Og
+else
+ CFLAGS += -O3 -fstrict-aliasing -Wstrict-aliasing
+endif
+
+INCLUDE_DIRS := -I.
+INCLUDE_DIRS += -I${FREERTOS_PLUS_DIR}/Source/FreeRTOS-Plus-TCP/portable/Compiler/GCC/
+INCLUDE_DIRS += -I$(KERNEL_DIR)/include
+INCLUDE_DIRS += -I$(KERNEL_DIR)/portable/GCC/ARM_CM3
+
+CFLAGS += $(DEFINES)
+CFLAGS += $(INCLUDE_DIRS)
+
+.PHONY:all
+
+%.d: %.c
+ @set -e; rm -f $@; \
+ $(CC) -M $(CPPFLAGS) $< > $@.$$$$; \
+ sed 's,\($*\)\.o[ :]*,\1.o $@ : ,g' < $@.$$$$ > $@; \
+ rm -f $@.$$$$
+
+${BUILD_DIR}/%.o : %.c Makefile
+ -mkdir -p $(@D)
+ $(CC) $(CFLAGS) -MMD -c $< -o $@
+
+$(BUILD_DIR)/$(BIN) : $(OBJ_FILES)
+ $(CC) -ffunction-sections -fdata-sections $(CFLAGS) $(LDFLAGS) $+ -o $(@)
+
+clean:
+ -rm -rf build
diff --git a/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/Readme.md b/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/Readme.md
new file mode 100644
index 000000000..5069ab378
--- /dev/null
+++ b/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/Readme.md
@@ -0,0 +1,47 @@
+# Emulating MPS2 Cortex M3 AN385 on QEMU
+
+## Requirements
+1. GNU Arm Embedded Toolchain download [here](https://developer.arm.com/tools-and-software/open-source-software/developer-tools/gnu-toolchain/gnu-rm/downloads)
+3. qemu-arm-system download [here](https://www.qemu.org/download)
+2. Make (tested on version 3.82)
+4. Linux OS (tested on Ubuntu 18.04)
+
+## How to build
+Navigate with the command line to FreeRTOS/Demo/CORTEX\_M3\_MPS2\_QEMU\_GCC
+For a release build run:
+
+```
+$ export PATH=/path/to/arm/toolchain:$PATH
+$ make
+```
+and for a versions with debugging symbols and no optimizations activated, run:
+```
+$ make DEBUG=1
+```
+
+## How to run
+run:
+```
+$ qemu-system-arm -machine mps2-an385 -monitor null -semihosting \
+ --semihosting-config enable=on,target=native \
+ -kernel ./build/RTOSDemo.axf \
+ -serial stdio -nographic
+```
+
+## How to start debugging (gdb)
+
+Append the -s and -S switches to the previous command (qemu-system-arm)
+-s: allow gdb to be attached to the process remotely at port 1234
+-S: start the program in the paused state
+
+run: (make sure you build the debug version)
+```
+$ arm-none-eabi-gdb -q ./build/RTOSDemo.axf
+
+(gdb) target remote :1234
+(gdb) break main
+(gdb) c
+```
+## Demo
+This Demo implements the blinky demo, the user should expect the word
+"blinking" to be repeatedly printed on the screen.
diff --git a/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/init/startup.c b/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/init/startup.c
new file mode 100644
index 000000000..750984cd2
--- /dev/null
+++ b/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/init/startup.c
@@ -0,0 +1,99 @@
+/*
+ * FreeRTOS Kernel V10.4.1
+ * Copyright (C) 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy of
+ * this software and associated documentation files (the "Software"), to deal in
+ * the Software without restriction, including without limitation the rights to
+ * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
+ * the Software, and to permit persons to whom the Software is furnished to do so,
+ * subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in all
+ * copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
+ * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
+ * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
+ * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
+ *
+ * https://www.FreeRTOS.org
+ * https://www.gihub.com/FreeRTOS
+ *
+ */
+
+#include
+#include
+#include
+#include
+
+extern uint32_t _estack, _sidata, _sdata, _edata, _sbss, _ebss;
+
+__attribute__((naked)) void Reset_Handler(void) {
+ // set stack pointer
+ __asm volatile ("ldr r0, =_estack");
+ __asm volatile ("mov sp, r0");
+ // copy .data section from flash to RAM
+ for (uint32_t *src = &_sidata, *dest = &_sdata; dest < &_edata;) {
+ *dest++ = *src++;
+ }
+ // zero out .bss section
+ for (uint32_t *dest = &_sbss; dest < &_ebss;) {
+ *dest++ = 0;
+ }
+ // jump to board initialisation
+ void _start(void);
+ _start();
+}
+
+void Default_Handler(void) {
+ for (;;) {
+ }
+}
+extern void vPortSVCHandler( void );
+extern void xPortPendSVHandler( void );
+extern void xPortSysTickHandler( void );
+
+const uint32_t isr_vector[] __attribute__((section(".isr_vector"))) = {
+ (uint32_t)&_estack,
+ (uint32_t)&Reset_Handler,
+ (uint32_t)&Default_Handler, // NMI_Handler
+ (uint32_t)&Default_Handler, // HardFault_Handler
+ (uint32_t)&Default_Handler, // MemManage_Handler
+ (uint32_t)&Default_Handler, // BusFault_Handler
+ (uint32_t)&Default_Handler, // UsageFault_Handler
+ 0,
+ 0,
+ 0,
+ 0,
+ (uint32_t)&vPortSVCHandler, // SVC_Handler
+ (uint32_t)&Default_Handler, // DebugMon_Handler
+ 0,
+ (uint32_t)&xPortPendSVHandler, // PendSV handler
+ (uint32_t)&xPortSysTickHandler, // SysTick_Handler
+};
+
+extern int main();
+extern void uart_init();
+void _start(void) {
+ uart_init();
+ main(0, 0);
+ exit(0);
+}
+
+__attribute__((naked)) void exit(int status) {
+ // Force qemu to exit using ARM Semihosting
+ __asm volatile (
+ "mov r1, r0\n"
+ "cmp r1, #0\n"
+ "bne .notclean\n"
+ "ldr r1, =0x20026\n" // ADP_Stopped_ApplicationExit, a clean exit
+ ".notclean:\n"
+ "movs r0, #0x18\n" // SYS_EXIT
+ "bkpt 0xab\n"
+ "end: b end\n"
+ );
+}
+
diff --git a/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/main.c b/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/main.c
new file mode 100644
index 000000000..8db28bab9
--- /dev/null
+++ b/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/main.c
@@ -0,0 +1,124 @@
+/*
+ * FreeRTOS Kernel V10.4.1
+ * Copyright (C) 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy of
+ * this software and associated documentation files (the "Software"), to deal in
+ * the Software without restriction, including without limitation the rights to
+ * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
+ * the Software, and to permit persons to whom the Software is furnished to do so,
+ * subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in all
+ * copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
+ * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
+ * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
+ * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
+ *
+ * https://www.FreeRTOS.org
+ * https://www.gihub.com/FreeRTOS
+ *
+ * 1 tab == 4 spaces!
+ */
+
+#include
+#include
+#include
+#define mainCREATE_SIMPLE_BLINKY_DEMO_ONLY 1
+
+void vApplicationMallocFailedHook( void );
+void vApplicationIdleHook( void );
+void vApplicationStackOverflowHook( TaskHandle_t pxTask, char *pcTaskName );
+void vApplicationTickHook( void );
+void main_blinky( void );
+
+int main ()
+{
+ main_blinky();
+ return 0;
+}
+
+/*-----------------------------------------------------------*/
+
+void vApplicationMallocFailedHook( void )
+{
+ /* Called if a call to pvPortMalloc() fails because there is insufficient
+ free memory available in the FreeRTOS heap. pvPortMalloc() is called
+ internally by FreeRTOS API functions that create tasks, queues, software
+ timers, and semaphores. The size of the FreeRTOS heap is set by the
+ configTOTAL_HEAP_SIZE configuration constant in FreeRTOSConfig.h. */
+ taskDISABLE_INTERRUPTS();
+ for( ;; );
+}
+/*-----------------------------------------------------------*/
+
+void vApplicationStackOverflowHook( TaskHandle_t pxTask, char *pcTaskName )
+{
+ ( void ) pcTaskName;
+ ( void ) pxTask;
+
+ /* Run time stack overflow checking is performed if
+ configCHECK_FOR_STACK_OVERFLOW is defined to 1 or 2. This hook
+ function is called if a stack overflow is detected. */
+ taskDISABLE_INTERRUPTS();
+ for( ;; );
+}
+/*-----------------------------------------------------------*/
+
+void vApplicationIdleHook( void )
+{
+volatile size_t xFreeHeapSpace;
+
+ /* This is just a trivial example of an idle hook. It is called on each
+ cycle of the idle task. It must *NOT* attempt to block. In this case the
+ idle task just queries the amount of FreeRTOS heap that remains. See the
+ memory management section on the http://www.FreeRTOS.org web site for memory
+ management options. If there is a lot of heap memory free then the
+ configTOTAL_HEAP_SIZE value in FreeRTOSConfig.h can be reduced to free up
+ RAM. */
+ xFreeHeapSpace = xPortGetFreeHeapSize();
+
+ /* Remove compiler warning about xFreeHeapSpace being set but never used. */
+ ( void ) xFreeHeapSpace;
+}
+/*-----------------------------------------------------------*/
+
+void vApplicationTickHook( void )
+{
+ #if( mainCREATE_SIMPLE_BLINKY_DEMO_ONLY == 0 )
+ {
+ /* The full demo includes a software timer demo/test that requires
+ prodding periodically from the tick interrupt. */
+ vTimerPeriodicISRTests();
+
+ /* Call the periodic queue overwrite from ISR demo. */
+ vQueueOverwritePeriodicISRDemo();
+
+ /* Call the periodic event group from ISR demo. */
+ vPeriodicEventGroupsProcessing();
+ }
+ #endif
+}
+/*-----------------------------------------------------------*/
+
+void vAssertCalled( void )
+{
+volatile unsigned long ul = 0;
+
+ taskENTER_CRITICAL();
+ {
+ /* Use the debugger to set ul to a non-zero value in order to step out
+ of this function to determine why it was called. */
+ while( ul == 0 )
+ {
+ portNOP();
+ }
+ }
+ taskEXIT_CRITICAL();
+}
+/*-----------------------------------------------------------*/
+
diff --git a/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/main_blinky.c b/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/main_blinky.c
new file mode 100644
index 000000000..1c555894e
--- /dev/null
+++ b/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/main_blinky.c
@@ -0,0 +1,131 @@
+/*
+ * FreeRTOS Kernel V10.4.1
+ * Copyright (C) 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy of
+ * this software and associated documentation files (the "Software"), to deal in
+ * the Software without restriction, including without limitation the rights to
+ * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
+ * the Software, and to permit persons to whom the Software is furnished to do so,
+ * subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in all
+ * copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
+ * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
+ * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
+ * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
+ *
+ * https://www.FreeRTOS.org
+ * https://www.gihub.com/FreeRTOS
+ *
+ * 1 tab == 4 spaces!
+ */
+
+#include
+#include
+#include
+#include
+
+static void prvQueueReceiveTask( void *pvParameters );
+static void prvQueueSendTask( void *pvParameters );
+extern int _write(int file, char *ptr, int len);
+
+#define mainQUEUE_RECEIVE_TASK_PRIORITY ( tskIDLE_PRIORITY + 2 )
+#define mainQUEUE_SEND_TASK_PRIORITY ( tskIDLE_PRIORITY + 1 )
+#define mainQUEUE_LENGTH ( 1 )
+#define mainQUEUE_SEND_FREQUENCY_MS ( 200 / portTICK_PERIOD_MS )
+/* The queue used by both tasks. */
+static QueueHandle_t xQueue = NULL;
+
+void main_blinky( void )
+{
+ /* Create the queue. */
+ xQueue = xQueueCreate( mainQUEUE_LENGTH, sizeof( uint32_t ) );
+
+ if( xQueue != NULL )
+ {
+ /* Start the two tasks as described in the comments at the top of this
+ file. */
+ xTaskCreate( prvQueueReceiveTask, /* The function that implements the task. */
+ "Rx", /* The text name assigned to the task - for debug only as it is not used by the kernel. */
+ configMINIMAL_STACK_SIZE, /* The size of the stack to allocate to the task. */
+ NULL, /* The parameter passed to the task - not used in this case. */
+ mainQUEUE_RECEIVE_TASK_PRIORITY, /* The priority assigned to the task. */
+ NULL ); /* The task handle is not required, so NULL is passed. */
+
+ xTaskCreate( prvQueueSendTask,
+ "TX",
+ configMINIMAL_STACK_SIZE,
+ NULL,
+ mainQUEUE_SEND_TASK_PRIORITY,
+ NULL );
+
+ /* Start the tasks and timer running. */
+ vTaskStartScheduler();
+ }
+
+ /* If all is well, the scheduler will now be running, and the following
+ line will never be reached. If the following line does execute, then
+ there was insufficient FreeRTOS heap memory available for the Idle and/or
+ timer tasks to be created. See the memory management section on the
+ FreeRTOS web site for more details on the FreeRTOS heap
+ http://www.freertos.org/a00111.html. */
+ for( ;; );
+}
+
+static void prvQueueSendTask( void *pvParameters )
+{
+TickType_t xNextWakeTime;
+const uint32_t ulValueToSend = 100UL;
+
+ /* Remove compiler warning about unused parameter. */
+ ( void ) pvParameters;
+
+ /* Initialise xNextWakeTime - this only needs to be done once. */
+ xNextWakeTime = xTaskGetTickCount();
+
+ for( ;; )
+ {
+ /* Place this task in the blocked state until it is time to run again. */
+ vTaskDelayUntil( &xNextWakeTime, mainQUEUE_SEND_FREQUENCY_MS );
+
+ /* Send to the queue - causing the queue receive task to unblock and
+ toggle the LED. 0 is used as the block time so the sending operation
+ will not block - it shouldn't need to block as the queue should always
+ be empty at this point in the code. */
+ xQueueSend( xQueue, &ulValueToSend, 0U );
+ }
+}
+
+volatile uint32_t ulRxEvents = 0;
+static void prvQueueReceiveTask( void *pvParameters )
+{
+uint32_t ulReceivedValue;
+const uint32_t ulExpectedValue = 100UL;
+
+ /* Remove compiler warning about unused parameter. */
+ ( void ) pvParameters;
+
+ for( ;; )
+ {
+ /* Wait until something arrives in the queue - this task will block
+ indefinitely provided INCLUDE_vTaskSuspend is set to 1 in
+ FreeRTOSConfig.h. */
+ xQueueReceive( xQueue, &ulReceivedValue, portMAX_DELAY );
+
+ /* To get here something must have been received from the queue, but
+ is it the expected value? If it is, toggle the LED. */
+ if( ulReceivedValue == ulExpectedValue )
+ {
+ _write(1, "blinking\n", 9);
+ vTaskDelay(1000);
+ ulReceivedValue = 0U;
+ ulRxEvents++;
+ }
+ }
+}
+/*-----------------------------------------------------------*/
diff --git a/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/scripts/mps2_m3.ld b/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/scripts/mps2_m3.ld
new file mode 100644
index 000000000..1b496a32b
--- /dev/null
+++ b/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/scripts/mps2_m3.ld
@@ -0,0 +1,101 @@
+/*
+ * FreeRTOS Kernel V10.4.1
+ * Copyright (C) 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy of
+ * this software and associated documentation files (the "Software"), to deal in
+ * the Software without restriction, including without limitation the rights to
+ * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
+ * the Software, and to permit persons to whom the Software is furnished to do so,
+ * subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in all
+ * copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
+ * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
+ * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
+ * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
+ *
+ * https://www.FreeRTOS.org
+ * https://www.gihub.com/FreeRTOS
+ *
+ */
+
+MEMORY
+{
+ RAM (xrw) : ORIGIN = 0x00000000, LENGTH = 4M
+}
+
+_Min_Heap_Size = 0x200 ; /* Required amount of heap. */
+_Min_Stack_Size = 0x400 ; /* Required amount of stack. */
+
+_estack = ORIGIN(RAM) + LENGTH(RAM);
+
+SECTIONS
+{
+ .text : {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector))
+ *(.text*)
+ KEEP (*(.init))
+ KEEP (*(.fini))
+ . = ALIGN(4);
+ _etext = .;
+ _sidata = _etext;
+ } > RAM
+
+ .data : AT ( _sidata )
+ {
+ . = ALIGN(4);
+ _sdata = .;
+ *(.data*)
+ *(.rodata*)
+ KEEP(*(.eh_frame))
+ . = ALIGN(4);
+ _edata = .;
+ } >RAM
+
+ .bss :
+ {
+ . = ALIGN(4);
+ _sbss = .;
+ __bss_start__ = _sbss;
+ *(.bss*)
+ *(COMMON)
+ . = ALIGN(4);
+ _ebss = .;
+ __bss_end__ = _ebss;
+ } >RAM
+
+ ._user_heap_stack :
+ {
+ . = ALIGN(8);
+ PROVIDE ( end = . );
+ PROVIDE ( _end = . );
+ _heap_bottom = .;
+ . = . + _Min_Heap_Size;
+ _heap_top = .;
+ . = . + _Min_Stack_Size;
+ . = ALIGN(8);
+ } >RAM
+
+ .ARM.extab :
+ {
+ . = ALIGN(4);
+ *(.ARM.extab* .gnu.linkonce.armextab.*)
+ . = ALIGN(4);
+ } >RAM
+
+ .ARM :
+ {
+ . = ALIGN(4);
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ . = ALIGN(4);
+ } >RAM
+}
+
diff --git a/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/syscall.c b/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/syscall.c
new file mode 100644
index 000000000..055a620d5
--- /dev/null
+++ b/FreeRTOS/Demo/CORTEX_M3_MPS2_QEMU_GCC/syscall.c
@@ -0,0 +1,111 @@
+/*
+ * FreeRTOS Kernel V10.4.1
+ * Copyright (C) 2020 Amazon.com, Inc. or its affiliates. All Rights Reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy of
+ * this software and associated documentation files (the "Software"), to deal in
+ * the Software without restriction, including without limitation the rights to
+ * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
+ * the Software, and to permit persons to whom the Software is furnished to do so,
+ * subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in all
+ * copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
+ * FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
+ * COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
+ * IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+ * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
+ *
+ * https://www.FreeRTOS.org
+ * https://www.gihub.com/FreeRTOS
+ *
+ */
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#include
+
+typedef struct UART_t {
+ volatile uint32_t DATA;
+ volatile uint32_t STATE;
+ volatile uint32_t CTRL;
+ volatile uint32_t INTSTATUS;
+ volatile uint32_t BAUDDIV;
+} UART_t;
+
+#define UART0_ADDR ((UART_t *)(0x40004000))
+#define UART_DR(baseaddr) (*(unsigned int *)(baseaddr))
+
+#define UART_STATE_TXFULL (1 << 0)
+#define UART_CTRL_TX_EN (1 << 0)
+#define UART_CTRL_RX_EN (1 << 1)
+
+static char *heap_end = 0;
+extern unsigned long _heap_bottom;
+extern unsigned long _heap_top;
+extern unsigned long g_ulBase;
+
+void uart_init()
+{
+ UART0_ADDR->BAUDDIV = 16;
+ UART0_ADDR->CTRL = UART_CTRL_TX_EN;
+}
+
+int _close(int file){
+ return -1;
+}
+
+int _fstat(int file){
+ return 0;
+}
+
+int _isatty(int file){
+ return 1;
+}
+
+int _lseek(int file, int buf, int dir){
+ return 0;
+}
+
+int _open(const char *name, int flags, int mode){
+ return -1;
+}
+
+int _read(int file, char *buf, int len){
+ return -1;
+}
+
+int _write(int file, char *buf, int len){
+ int todo;
+
+ for (todo = 0; todo < len; todo++){
+ UART_DR(UART0_ADDR) = *buf++;
+ }
+ return len;
+}
+
+caddr_t _sbrk(unsigned int incr){
+ char *prev_heap_end;
+
+ if (heap_end == 0){
+ heap_end = (caddr_t)&_heap_bottom;
+ }
+
+ prev_heap_end = heap_end;
+
+ if (heap_end + incr > (caddr_t)&_heap_top){
+ return (caddr_t)0;
+ }
+
+ heap_end += incr;
+
+ return (caddr_t) prev_heap_end;
+}
+
+#ifdef __cplusplus
+}
+#endif