diff --git a/README.md b/README.md
index 552a2e87374..fb4926b7217 100644
--- a/README.md
+++ b/README.md
@@ -35,8 +35,9 @@ NXP:
* LPC11C24 (Cortex-M0)
Freescale:
-* [KL25Z](http://mbed.org/platforms/KL25Z/) (Cortex-M0+)
* KL05Z (Cortex-M0+)
+* [KL25Z](http://mbed.org/platforms/KL25Z/) (Cortex-M0+)
+* KL46Z (Cortex-M0+)
STMicroelectronics:
* STM32F407 (Cortex-M4)
diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_KL05Z/TOOLCHAIN_GCC_ARM/MKL05Z4.ld b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_KL05Z/TOOLCHAIN_GCC_ARM/MKL05Z4.ld
new file mode 100644
index 00000000000..5585ee7b837
--- /dev/null
+++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_KL05Z/TOOLCHAIN_GCC_ARM/MKL05Z4.ld
@@ -0,0 +1,154 @@
+/*
+ * KL05Z ARM GCC linker script file, Martin Kojtal (0xc0170)
+ */
+
+MEMORY
+{
+ VECTORS (rx) : ORIGIN = 0x00000000, LENGTH = 0x00000410
+ FLASH (rx) : ORIGIN = 0x00000410, LENGTH = 32K - 0x00000410
+ RAM (rwx) : ORIGIN = 0x1FFFFC00, LENGTH = 4K - 0xC0
+}
+
+/* Linker script to place sections and symbol values. Should be used together
+ * with other linker script that defines memory regions FLASH and RAM.
+ * It references following symbols, which must be defined in code:
+ * _reset_init : Entry of reset handler
+ *
+ * It defines following symbols, which code can use without definition:
+ * __exidx_start
+ * __exidx_end
+ * __etext
+ * __data_start__
+ * __preinit_array_start
+ * __preinit_array_end
+ * __init_array_start
+ * __init_array_end
+ * __fini_array_start
+ * __fini_array_end
+ * __data_end__
+ * __bss_start__
+ * __bss_end__
+ * __end__
+ * end
+ * __HeapLimit
+ * __StackLimit
+ * __StackTop
+ * __stack
+ */
+ENTRY(Reset_Handler)
+
+SECTIONS
+{
+ .isr_vector :
+ {
+ __vector_table = .;
+ KEEP(*(.vector_table))
+ . = ALIGN(4);
+ } > VECTORS
+
+ .text :
+ {
+ *(.text*)
+
+ KEEP(*(.init))
+ KEEP(*(.fini))
+
+ /* .ctors */
+ *crtbegin.o(.ctors)
+ *crtbegin?.o(.ctors)
+ *(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors)
+ *(SORT(.ctors.*))
+ *(.ctors)
+
+ /* .dtors */
+ *crtbegin.o(.dtors)
+ *crtbegin?.o(.dtors)
+ *(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors)
+ *(SORT(.dtors.*))
+ *(.dtors)
+
+ *(.rodata*)
+
+ KEEP(*(.eh_frame*))
+ } > FLASH
+
+ .ARM.extab :
+ {
+ *(.ARM.extab* .gnu.linkonce.armextab.*)
+ } > FLASH
+
+ __exidx_start = .;
+ .ARM.exidx :
+ {
+ *(.ARM.exidx* .gnu.linkonce.armexidx.*)
+ } > FLASH
+ __exidx_end = .;
+
+ __etext = .;
+
+ .data : AT (__etext)
+ {
+ __data_start__ = .;
+ *(vtable)
+ *(.data*)
+
+ . = ALIGN(4);
+ /* preinit data */
+ PROVIDE_HIDDEN (__preinit_array_start = .);
+ KEEP(*(.preinit_array))
+ PROVIDE_HIDDEN (__preinit_array_end = .);
+
+ . = ALIGN(4);
+ /* init data */
+ PROVIDE_HIDDEN (__init_array_start = .);
+ KEEP(*(SORT(.init_array.*)))
+ KEEP(*(.init_array))
+ PROVIDE_HIDDEN (__init_array_end = .);
+
+
+ . = ALIGN(4);
+ /* finit data */
+ PROVIDE_HIDDEN (__fini_array_start = .);
+ KEEP(*(SORT(.fini_array.*)))
+ KEEP(*(.fini_array))
+ PROVIDE_HIDDEN (__fini_array_end = .);
+
+ . = ALIGN(4);
+ /* All data end */
+ __data_end__ = .;
+
+ } > RAM
+
+ .bss :
+ {
+ __bss_start__ = .;
+ *(.bss*)
+ *(COMMON)
+ __bss_end__ = .;
+ } > RAM
+
+ .heap :
+ {
+ __end__ = .;
+ end = __end__;
+ *(.heap*)
+ __HeapLimit = .;
+ } > RAM
+
+ /* .stack_dummy section doesn't contains any symbols. It is only
+ * used for linker to calculate size of stack sections, and assign
+ * values to stack symbols later */
+ .stack_dummy :
+ {
+ *(.stack)
+ } > RAM
+
+ /* Set stack top to end of RAM, and stack limit move down by
+ * size of stack_dummy section */
+ __StackTop = ORIGIN(RAM) + LENGTH(RAM);
+ __StackLimit = __StackTop - SIZEOF(.stack_dummy);
+ PROVIDE(__stack = __StackTop);
+
+ /* Check if data + heap + stack exceeds RAM limit */
+ ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed with stack")
+}
diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_KL05Z/TOOLCHAIN_GCC_ARM/startup_MKL05Z4.s b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_KL05Z/TOOLCHAIN_GCC_ARM/startup_MKL05Z4.s
new file mode 100644
index 00000000000..384c489e2e4
--- /dev/null
+++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_KL05Z/TOOLCHAIN_GCC_ARM/startup_MKL05Z4.s
@@ -0,0 +1,225 @@
+/* KL05Z startup ARM GCC, Martin Kojtal (0xc0170)
+ * Purpose: startup file for Cortex-M0 devices. Should use with
+ * GCC for ARM Embedded Processors
+ * Version: V1.2
+ * Date: 15 Nov 2011
+ *
+ * Copyright (c) 2011, ARM Limited
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ * 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.
+ * Neither the name of the ARM Limited nor the
+ names of its contributors may be used to endorse or promote products
+ derived from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS 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 ARM LIMITED 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.
+ */
+ .syntax unified
+ .arch armv6-m
+
+/* Memory Model
+ The HEAP starts at the end of the DATA section and grows upward.
+
+ The STACK starts at the end of the RAM and grows downward.
+
+ The HEAP and stack STACK are only checked at compile time:
+ (DATA_SIZE + HEAP_SIZE + STACK_SIZE) < RAM_SIZE
+
+ This is just a check for the bare minimum for the Heap+Stack area before
+ aborting compilation, it is not the run time limit:
+ Heap_Size + Stack_Size = 0x80 + 0x80 = 0x100
+ */
+ .section .stack
+ .align 3
+#ifdef __STACK_SIZE
+ .equ Stack_Size, __STACK_SIZE
+#else
+ .equ Stack_Size, 0x80
+#endif
+ .globl __StackTop
+ .globl __StackLimit
+__StackLimit:
+ .space Stack_Size
+ .size __StackLimit, . - __StackLimit
+__StackTop:
+ .size __StackTop, . - __StackTop
+
+ .section .heap
+ .align 3
+#ifdef __HEAP_SIZE
+ .equ Heap_Size, __HEAP_SIZE
+#else
+ .equ Heap_Size, 0x80
+#endif
+ .globl __HeapBase
+ .globl __HeapLimit
+__HeapBase:
+ .space Heap_Size
+ .size __HeapBase, . - __HeapBase
+__HeapLimit:
+ .size __HeapLimit, . - __HeapLimit
+
+ .section .vector_table,"a",%progbits
+ .align 2
+ .globl __isr_vector
+__isr_vector:
+ .long __StackTop /* Top of Stack */
+ .long Reset_Handler /* Reset Handler */
+ .long NMI_Handler /* NMI Handler */
+ .long HardFault_Handler /* Hard Fault Handler */
+ .long 0 /* Reserved */
+ .long 0 /* Reserved */
+ .long 0 /* Reserved */
+ .long 0 /* Reserved */
+ .long 0 /* Reserved */
+ .long 0 /* Reserved */
+ .long 0 /* Reserved */
+ .long SVC_Handler /* SVCall Handler */
+ .long 0 /* Reserved */
+ .long 0 /* Reserved */
+ .long PendSV_Handler /* PendSV Handler */
+ .long SysTick_Handler /* SysTick Handler */
+
+ /* External interrupts */
+ .long DMA0_IRQHandler /* DMA channel 0 transfer complete interrupt */
+ .long DMA1_IRQHandler /* DMA channel 1 transfer complete interrupt */
+ .long DMA2_IRQHandler /* DMA channel 2 transfer complete interrupt */
+ .long DMA3_IRQHandler /* DMA channel 3 transfer complete interrupt */
+ .long Default_Handler /* Reserved interrupt 20 */
+ .long FTFA_IRQHandler /* FTFA interrupt */
+ .long LVD_LVW_IRQHandler /* Low Voltage Detect, Low Voltage Warning */
+ .long LLW_IRQHandler /* Low Leakage Wakeup */
+ .long I2C0_IRQHandler /* I2C0 interrupt */
+ .long Default_Handler /* Reserved interrupt 25 */
+ .long SPI0_IRQHandler /* SPI0 interrupt */
+ .long Default_Handler /* Reserved interrupt 27 */
+ .long UART0_IRQHandler /* UART0 status/error interrupt */
+ .long Default_Handler /* Reserved interrupt 29 */
+ .long Default_Handler /* Reserved interrupt 30 */
+ .long ADC0_IRQHandler /* ADC0 interrupt */
+ .long CMP0_IRQHandler /* CMP0 interrupt */
+ .long TPM0_IRQHandler /* TPM0 fault, overflow and channels interrupt */
+ .long TPM1_IRQHandler /* TPM1 fault, overflow and channels interrupt */
+ .long Default_Handler /* Reserved interrupt 35 */
+ .long RTC_IRQHandler /* RTC interrupt */
+ .long RTC_Seconds_IRQHandler /* RTC seconds interrupt */
+ .long PIT_IRQHandler /* PIT timer interrupt */
+ .long Default_Handler /* Reserved interrupt 39 */
+ .long Default_Handler /* Reserved interrupt 40 */
+ .long DAC0_IRQHandler /* DAC interrupt */
+ .long TSI0_IRQHandler /* TSI0 interrupt */
+ .long MCG_IRQHandler /* MCG interrupt */
+ .long LPTimer_IRQHandler /* LPTimer interrupt */
+ .long Default_Handler /* Reserved interrupt 45 */
+ .long PORTA_IRQHandler /* Port A interrupt */
+ .long PORTB_IRQHandler /* Port B interrupt */
+
+ .size __isr_vector, . - __isr_vector
+ .org 0x400, 0xff
+
+ .long 0xffffffff
+ .long 0xffffffff
+ .long 0xffffffff
+ .long 0xfffffffe
+
+ .section .text.Reset_Handler
+ .thumb
+ .thumb_func
+ .align 2
+ .globl Reset_Handler
+ .type Reset_Handler, %function
+Reset_Handler:
+/* Loop to copy data from read only memory to RAM. The ranges
+ * of copy from/to are specified by following symbols evaluated in
+ * linker script.
+ * __etext: End of code section, i.e., begin of data sections to copy from.
+ * __data_start__/__data_end__: RAM address range that data should be
+ * copied to. Both must be aligned to 4 bytes boundary. */
+
+ ldr r1, =__etext
+ ldr r2, =__data_start__
+ ldr r3, =__data_end__
+
+ subs r3, r2
+ ble .flash_to_ram_loop_end
+
+ movs r4, 0
+.flash_to_ram_loop:
+ ldr r0, [r1,r4]
+ str r0, [r2,r4]
+ adds r4, 4
+ cmp r4, r3
+ blt .flash_to_ram_loop
+.flash_to_ram_loop_end:
+
+ ldr r0, =SystemInit
+ blx r0
+ ldr r0, =_start
+ bx r0
+ .pool
+ .size Reset_Handler, . - Reset_Handler
+
+ .text
+/* Macro to define default handlers. Default handler
+ * will be weak symbol and just dead loops. They can be
+ * overwritten by other handlers */
+ .macro def_default_handler handler_name
+ .align 1
+ .thumb_func
+ .weak \handler_name
+ .type \handler_name, %function
+\handler_name :
+ b .
+ .size \handler_name, . - \handler_name
+ .endm
+
+ def_default_handler NMI_Handler
+ def_default_handler HardFault_Handler
+ def_default_handler SVC_Handler
+ def_default_handler PendSV_Handler
+ def_default_handler SysTick_Handler
+ def_default_handler Default_Handler
+
+ def_default_handler DMA0_IRQHandler
+ def_default_handler DMA1_IRQHandler
+ def_default_handler DMA2_IRQHandler
+ def_default_handler DMA3_IRQHandler
+ def_default_handler FTFA_IRQHandler
+ def_default_handler LVD_LVW_IRQHandler
+ def_default_handler LLW_IRQHandler
+ def_default_handler I2C0_IRQHandler
+ def_default_handler SPI0_IRQHandler
+ def_default_handler UART0_IRQHandler
+ def_default_handler ADC0_IRQHandler
+ def_default_handler CMP0_IRQHandler
+ def_default_handler TPM0_IRQHandler
+ def_default_handler TPM1_IRQHandler
+ def_default_handler RTC_IRQHandler
+ def_default_handler RTC_Seconds_IRQHandler
+ def_default_handler PIT_IRQHandler
+ def_default_handler DAC0_IRQHandler
+ def_default_handler TSI0_IRQHandler
+ def_default_handler MCG_IRQHandler
+ def_default_handler LPTimer_IRQHandler
+ def_default_handler PORTA_IRQHandler
+ def_default_handler PORTB_IRQHandler
+
+ .weak DEF_IRQHandler
+ .set DEF_IRQHandler, Default_Handler
+
+ .end
diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_KL05Z/us_ticker.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_KL05Z/us_ticker.c
index f4a99cf2b88..9253313a448 100644
--- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_KL05Z/us_ticker.c
+++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_KL05Z/us_ticker.c
@@ -114,7 +114,7 @@ static void lptmr_isr(void) {
}
}
-void us_ticker_set_interrupt(uint32_t timestamp) {
+void us_ticker_set_interrupt(unsigned int timestamp) {
int32_t delta = (int32_t)(timestamp - us_ticker_read());
if (delta <= 0) {
// This event was in the past:
diff --git a/workspace_tools/export/gcc_arm_kl05z.tmpl b/workspace_tools/export/gcc_arm_kl05z.tmpl
new file mode 100644
index 00000000000..f4dd6338717
--- /dev/null
+++ b/workspace_tools/export/gcc_arm_kl05z.tmpl
@@ -0,0 +1,46 @@
+# This file was automagically generated by mbed.org. For more information,
+# see http://mbed.org/handbook/Exporting-to-GCC-ARM-Embedded
+
+GCC_BIN =
+PROJECT = {{name}}
+OBJECTS = {% for f in to_be_compiled %}{{f}} {% endfor %}
+SYS_OBJECTS = {% for f in object_files %}{{f}} {% endfor %}
+INCLUDE_PATHS = {% for p in include_paths %}-I{{p}} {% endfor %}
+LIBRARY_PATHS = {% for p in library_paths %}-L{{p}} {% endfor %}
+LIBRARIES = {% for lib in libraries %}-l{{lib}} {% endfor %}
+LINKER_SCRIPT = {{linker_script}}
+
+###############################################################################
+AS = $(GCC_BIN)arm-none-eabi-as
+CC = $(GCC_BIN)arm-none-eabi-gcc
+CPP = $(GCC_BIN)arm-none-eabi-g++
+LD = $(GCC_BIN)arm-none-eabi-gcc
+OBJCOPY = $(GCC_BIN)arm-none-eabi-objcopy
+
+CPU = -mcpu=cortex-m0plus -mthumb
+CC_FLAGS = $(CPU) -c -Os -fno-common -fmessage-length=0 -Wall -fno-exceptions -ffunction-sections -fdata-sections
+CC_SYMBOLS = {% for s in symbols %}-D{{s}} {% endfor %}
+
+LD_FLAGS = -mcpu=cortex-m0plus -mthumb -Wl,--gc-sections --specs=nano.specs -u _printf_float -u _scanf_float
+LD_SYS_LIBS = -lstdc++ -lsupc++ -lm -lc -lgcc -lnosys
+
+all: $(PROJECT).bin
+
+clean:
+ rm -f $(PROJECT).bin $(PROJECT).elf $(OBJECTS)
+
+.s.o:
+ $(AS) $(CPU) -o $@ $<
+
+.c.o:
+ $(CC) $(CC_FLAGS) $(CC_SYMBOLS) -std=gnu99 $(INCLUDE_PATHS) -o $@ $<
+
+.cpp.o:
+ $(CPP) $(CC_FLAGS) $(CC_SYMBOLS) -std=gnu++98 $(INCLUDE_PATHS) -o $@ $<
+
+
+$(PROJECT).elf: $(OBJECTS) $(SYS_OBJECTS)
+ $(LD) $(LD_FLAGS) -T$(LINKER_SCRIPT) $(LIBRARY_PATHS) -o $@ $^ $(LIBRARIES) $(LD_SYS_LIBS) $(LIBRARIES) $(LD_SYS_LIBS)
+
+$(PROJECT).bin: $(PROJECT).elf
+ $(OBJCOPY) -O binary $< $@
diff --git a/workspace_tools/export/gccarm.py b/workspace_tools/export/gccarm.py
index 19ba98350a7..85f40478d70 100644
--- a/workspace_tools/export/gccarm.py
+++ b/workspace_tools/export/gccarm.py
@@ -21,7 +21,7 @@
class GccArm(Exporter):
NAME = 'GccArm'
TOOLCHAIN = 'GCC_ARM'
- TARGETS = ['LPC1768','KL25Z','KL46Z','LPC4088']
+ TARGETS = ['LPC1768','KL05Z','KL25Z','KL46Z','LPC4088']
DOT_IN_RELATIVE_PATH = True
def generate(self):
diff --git a/workspace_tools/export/uvision4.py b/workspace_tools/export/uvision4.py
index 01202bd414c..3ab36b0c951 100644
--- a/workspace_tools/export/uvision4.py
+++ b/workspace_tools/export/uvision4.py
@@ -21,7 +21,7 @@
class Uvision4(Exporter):
NAME = 'uVision4'
- TARGETS = ['LPC1768', 'LPC11U24', 'KL25Z', 'KL46Z', 'LPC1347', 'LPC1114', 'LPC11C24', 'LPC4088', 'LPC812', 'NUCLEO_F103RB']
+ TARGETS = ['LPC1768', 'LPC11U24', 'KL05Z', 'KL25Z', 'KL46Z', 'LPC1347', 'LPC1114', 'LPC11C24', 'LPC4088', 'LPC812', 'NUCLEO_F103RB']
USING_MICROLIB = ['LPC11U24', 'LPC1114', 'LPC11C24', 'LPC812', 'NUCLEO_F103RB']
diff --git a/workspace_tools/export/uvision4_kl05z.uvopt.tmpl b/workspace_tools/export/uvision4_kl05z.uvopt.tmpl
new file mode 100644
index 00000000000..6eb495bc9d5
--- /dev/null
+++ b/workspace_tools/export/uvision4_kl05z.uvopt.tmpl
@@ -0,0 +1,204 @@
+
+
+
+ 1.0
+
+ ### uVision Project, (C) Keil Software
+
+
+ *.c
+ *.s*; *.src; *.a*
+ *.obj
+ *.lib
+ *.txt; *.h; *.inc
+ *.plm
+ *.cpp
+
+
+
+ 0
+ 0
+
+
+
+ mbed FRDM-KL05Z
+ 0x4
+ ARM-ADS
+
+ 8000000
+
+ 1
+ 1
+ 1
+ 0
+
+
+ 1
+ 65535
+ 0
+ 0
+ 0
+
+
+ 79
+ 66
+ 8
+ .\build\
+
+
+ 1
+ 1
+ 1
+ 0
+ 1
+ 1
+ 0
+ 1
+ 0
+ 0
+ 0
+ 0
+
+
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 0
+ 0
+
+
+ 1
+ 0
+ 1
+
+ 14
+
+
+ 0
+ Data Sheet
+ DATASHTS\Freescale\KL05PB.pdf
+
+
+ 1
+ Technical Reference Manual
+ datashts\arm\cortex_m0p\r0p0\DDI0484B_CORTEX_M0P_R0P0_TRM.PDF
+
+
+ 2
+ Generic User Guide
+ datashts\arm\cortex_m0p\r0p0\DUI0662A_CORTEX_M0P_R0P0_DGUG.PDF
+
+
+
+ SARMCM3.DLL
+
+ DARMCM1.DLL
+ -pCM0+
+ SARMCM3.DLL
+
+ TARMCM1.DLL
+ -pCM0+
+
+
+
+ 0
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 0
+ 1
+ 0
+ 0
+ 14
+
+
+
+
+
+
+
+
+
+
+ BIN\CMSIS_AGDI.dll
+
+
+
+ 0
+ ULP2CM3
+ -O2510 -S0 -C0 -FO15 -FD20000000 -FC800 -FN1 -FF0MK_P32_48MHZ -FS00 -FL008000)
+
+
+ 0
+ CMSIS_AGDI
+ -X"MBED CMSIS-DAP" -UA000000001 -O462 -S0 -C0 -N00("ARM CoreSight SW-DP") -D00(0BC11477) -L00(0) -FO15 -FD20000000 -FC800 -FN1 -FF0MK_P32_48MHZ -FS00 -FL08000
+
+
+
+
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+
+
+
+
+
+
+
+ src
+ 1
+ 0
+ 0
+
+ 1
+ 1
+ 8
+ 0
+ 0
+ 0
+ 0
+ 1
+ 2
+ 0
+ main.cpp
+ main.cpp
+
+
+
+
diff --git a/workspace_tools/export/uvision4_kl05z.uvproj.tmpl b/workspace_tools/export/uvision4_kl05z.uvproj.tmpl
new file mode 100644
index 00000000000..f6faf306e3a
--- /dev/null
+++ b/workspace_tools/export/uvision4_kl05z.uvproj.tmpl
@@ -0,0 +1,423 @@
+
+
+
+ 1.1
+
+ ###This file was automagically generated by mbed.org. For more information, see http://mbed.org/handbook/Exporting-To-Uvision
+
+
+
+ mbed FRDM-KL05Z
+ 0x4
+ ARM-ADS
+
+
+ MKL05Z32xxx4
+ Freescale Semiconductor
+ IRAM(0x1FFFFC00-0x1FFFFFFF) IRAM2(0x20000000-0x20000BFF) IROM(0x0-0x07FFF) CLOCK(8000000) CPUTYPE("Cortex-M0+") ELITTLE
+
+ "STARTUP\Freescale\Kinetis\startup_MKL05Z4.s" ("Freescale MKL05Zxxxxxx4 Startup Code")
+ ULP2CM3(-O2510 -S0 -C0 -FO15 -FD20000000 -FC800 -FN1 -FF0MK_P32_48MHZ -FS00 -FL08000)
+ 6544
+ MKL05Z4.H
+
+
+
+
+
+
+
+
+
+ SFD\Freescale\Kinetis\MKL05Z4.sfr
+ 0
+
+
+
+ Freescale\Kinetis\
+ Freescale\Kinetis\
+
+ 0
+ 0
+ 0
+ 0
+ 1
+
+ .\build\
+ {{name}}
+ 1
+ 0
+ 0
+ 1
+ 1
+ .\build\
+ 1
+ 0
+ 0
+
+ 0
+ 0
+
+
+ 0
+ 0
+ 0
+ 0
+
+
+ 0
+ 0
+
+
+ 0
+ 0
+
+
+ 1
+ 0
+ fromelf --bin -o build\{{name}}_KL05Z.bin build\{{name}}.axf
+
+ 0
+ 0
+
+ 0
+
+
+
+ 0
+ 0
+ 0
+ 0
+ 0
+ 1
+ 0
+ 0
+ 0
+ 0
+ 3
+
+
+
+
+ SARMCM3.DLL
+
+ DARMCM1.DLL
+ -pCM0+
+ SARMCM3.DLL
+
+ TARMCM1.DLL
+ -pCM0+
+
+
+
+ 1
+ 0
+ 0
+ 0
+ 16
+
+
+ 0
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 0
+
+
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 0
+ 1
+
+ 0
+ 14
+
+
+
+
+
+
+
+
+
+
+
+
+
+ BIN\CMSIS_AGDI.dll
+
+
+
+
+ 1
+ 0
+ 0
+ 1
+ 1
+ 4105
+
+ BIN\CMSIS_AGDI.dll
+ "" ()
+
+
+
+
+ 0
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 0
+ 1
+ 1
+ 0
+ 1
+ 1
+ 0
+ 0
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 1
+ 0
+ 0
+ "Cortex-M0+"
+
+ 0
+ 0
+ 0
+ 1
+ 1
+ 0
+ 0
+ 0
+ 1
+ 0
+ 8
+ 0
+ 0
+ 0
+ 3
+ 3
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 1
+ 0
+ 0
+ 0
+ 0
+ 1
+ 0
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 0
+ 0x1ffffc00
+ 0x400
+
+
+ 1
+ 0x0
+ 0x8000
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 1
+ 0x0
+ 0x0
+
+
+ 1
+ 0x0
+ 0x0
+
+
+ 1
+ 0x0
+ 0x0
+
+
+ 1
+ 0x0
+ 0x8000
+
+
+ 1
+ 0x0
+ 0x0
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 0
+ 0x0
+ 0x0
+
+
+ 0
+ 0x1ffffc00
+ 0x400
+
+
+ 0
+ 0x0
+ 0x0
+
+
+
+
+
+ 1
+ 1
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+
+ --gnu
+ {% for s in symbols %} {{s}}, {% endfor %}
+
+ {% for path in include_paths %} {{path}}; {% endfor %}
+
+
+
+ 1
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+
+
+
+
+
+
+
+
+ 0
+ 0
+ 0
+ 0
+ 1
+ 0
+ 0x00000000
+ 0x10000000
+ {{scatter_file}}
+
+
+
+ {% for file in object_files %}
+ {{file}}
+ {% endfor %}
+
+
+
+
+
+
+
+ {% for group,files in source_files %}
+
+ {{group}}
+
+ {% for file in files %}
+
+ {{file.name}}
+ {{file.type}}
+ {{file.path}}
+ {%if file.type == "1" %}
+
+
+
+
+ --c99
+
+
+
+
+ {% endif %}
+
+ {% endfor %}
+
+
+ {% endfor %}
+
+
+
+
+
diff --git a/workspace_tools/targets.py b/workspace_tools/targets.py
index f3c77dfe9f3..5efdbb7d5fc 100644
--- a/workspace_tools/targets.py
+++ b/workspace_tools/targets.py
@@ -106,7 +106,7 @@ def __init__(self):
self.extra_labels = ['Freescale']
- self.supported_toolchains = ["ARM"]
+ self.supported_toolchains = ["ARM", "GCC_ARM"]
self.is_disk_virtual = True