pull/496/head
bcostm 2014-09-22 10:41:28 +02:00
commit 362f0ce335
25 changed files with 2098 additions and 446 deletions

View File

@ -0,0 +1,164 @@
/*
* K64F ARM GCC linker script file
*/
MEMORY
{
VECTORS (rx) : ORIGIN = 0x00000000, LENGTH = 0x00000400
FLASH_PROTECTION (rx) : ORIGIN = 0x00000400, LENGTH = 0x00000010
FLASH (rx) : ORIGIN = 0x00000410, LENGTH = 0x000080000 - 0x00000410
RAM (rwx) : ORIGIN = 0x1FFF0400, LENGTH = 0x000020000 - 0x00000400
}
/* 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))
*(.text.Reset_Handler)
*(.text.System_Init)
. = ALIGN(4);
} > VECTORS
.flash_protect :
{
KEEP(*(.kinetis_flash_config_field))
. = ALIGN(4);
} > FLASH_PROTECTION
.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")
}

View File

@ -0,0 +1,369 @@
/* K64F startup ARM GCC
* Purpose: startup file for Cortex-M4 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 armv7-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, 0xC00
#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, 0x400
#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 MemManage_Handler /* MPU Fault Handler */
.long BusFault_Handler /* Bus Fault Handler */
.long UsageFault_Handler /* Usage Fault Handler */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long SVC_Handler /* SVCall Handler */
.long DebugMon_Handler /* Debug Monitor Handler */
.long 0 /* Reserved */
.long PendSV_Handler /* PendSV Handler */
.long SysTick_Handler /* SysTick Handler */
/* External Interrupts */
.long DMA0_IRQHandler /* DMA Channel 0 Transfer Complete*/
.long DMA1_IRQHandler /* DMA Channel 1 Transfer Complete*/
.long DMA2_IRQHandler /* DMA Channel 2 Transfer Complete*/
.long DMA3_IRQHandler /* DMA Channel 3 Transfer Complete*/
.long DMA4_IRQHandler /* DMA Channel 4 Transfer Complete*/
.long DMA5_IRQHandler /* DMA Channel 5 Transfer Complete*/
.long DMA6_IRQHandler /* DMA Channel 6 Transfer Complete*/
.long DMA7_IRQHandler /* DMA Channel 7 Transfer Complete*/
.long DMA8_IRQHandler /* DMA Channel 8 Transfer Complete*/
.long DMA9_IRQHandler /* DMA Channel 9 Transfer Complete*/
.long DMA10_IRQHandler /* DMA Channel 10 Transfer Complete*/
.long DMA11_IRQHandler /* DMA Channel 11 Transfer Complete*/
.long DMA12_IRQHandler /* DMA Channel 12 Transfer Complete*/
.long DMA13_IRQHandler /* DMA Channel 13 Transfer Complete*/
.long DMA14_IRQHandler /* DMA Channel 14 Transfer Complete*/
.long DMA15_IRQHandler /* DMA Channel 15 Transfer Complete*/
.long DMA_Error_IRQHandler /* DMA Error Interrupt*/
.long MCM_IRQHandler /* Normal Interrupt*/
.long FTF_IRQHandler /* FTFA Command complete interrupt*/
.long Read_Collision_IRQHandler /* Read Collision Interrupt*/
.long LVD_LVW_IRQHandler /* Low Voltage Detect, Low Voltage Warning*/
.long LLW_IRQHandler /* Low Leakage Wakeup*/
.long Watchdog_IRQHandler /* WDOG Interrupt*/
.long RNG_IRQHandler /* RNG Interrupt*/
.long I2C0_IRQHandler /* I2C0 interrupt*/
.long I2C1_IRQHandler /* I2C1 interrupt*/
.long SPI0_IRQHandler /* SPI0 Interrupt*/
.long SPI1_IRQHandler /* SPI1 Interrupt*/
.long I2S0_Tx_IRQHandler /* I2S0 transmit interrupt*/
.long I2S0_Rx_IRQHandler /* I2S0 receive interrupt*/
.long LPUART0_IRQHandler /* LPUART0 status/error interrupt*/
.long UART0_RX_TX_IRQHandler /* UART0 Receive/Transmit interrupt*/
.long UART0_ERR_IRQHandler /* UART0 Error interrupt*/
.long UART1_RX_TX_IRQHandler /* UART1 Receive/Transmit interrupt*/
.long UART1_ERR_IRQHandler /* UART1 Error interrupt*/
.long UART2_RX_TX_IRQHandler /* UART2 Receive/Transmit interrupt*/
.long UART2_ERR_IRQHandler /* UART2 Error interrupt*/
.long Reserved53_IRQHandler /* Reserved interrupt 53*/
.long Reserved54_IRQHandler /* Reserved interrupt 54*/
.long ADC0_IRQHandler /* ADC0 interrupt*/
.long CMP0_IRQHandler /* CMP0 interrupt*/
.long CMP1_IRQHandler /* CMP1 interrupt*/
.long FTM0_IRQHandler /* FTM0 fault, overflow and channels interrupt*/
.long FTM1_IRQHandler /* FTM1 fault, overflow and channels interrupt*/
.long FTM2_IRQHandler /* FTM2 fault, overflow and channels interrupt*/
.long Reserved61_IRQHandler /* Reserved interrupt 61*/
.long RTC_IRQHandler /* RTC interrupt*/
.long RTC_Seconds_IRQHandler /* RTC seconds interrupt*/
.long PIT0_IRQHandler /* PIT timer channel 0 interrupt*/
.long PIT1_IRQHandler /* PIT timer channel 1 interrupt*/
.long PIT2_IRQHandler /* PIT timer channel 2 interrupt*/
.long PIT3_IRQHandler /* PIT timer channel 3 interrupt*/
.long PDB0_IRQHandler /* PDB0 Interrupt*/
.long USB0_IRQHandler /* USB0 interrupt*/
.long Reserved70_IRQHandler /* Reserved interrupt 70*/
.long Reserved71_IRQHandler /* Reserved interrupt 71*/
.long DAC0_IRQHandler /* DAC0 interrupt*/
.long MCG_IRQHandler /* MCG Interrupt*/
.long LPTimer_IRQHandler /* LPTimer interrupt*/
.long PORTA_IRQHandler /* Port A interrupt*/
.long PORTB_IRQHandler /* Port B interrupt*/
.long PORTC_IRQHandler /* Port C interrupt*/
.long PORTD_IRQHandler /* Port D interrupt*/
.long PORTE_IRQHandler /* Port E interrupt*/
.long SWI_IRQHandler /* Software interrupt*/
.long Reserved81_IRQHandler /* Reserved interrupt 81*/
.long Reserved82_IRQHandler /* Reserved interrupt 82*/
.long Reserved83_IRQHandler /* Reserved interrupt 83*/
.long Reserved84_IRQHandler /* Reserved interrupt 84*/
.long Reserved85_IRQHandler /* Reserved interrupt 85*/
.long Reserved86_IRQHandler /* Reserved interrupt 86*/
.long FTM3_IRQHandler /* FTM3 fault, overflow and channels interrupt*/
.long DAC1_IRQHandler /* DAC1 interrupt*/
.long ADC1_IRQHandler /* ADC1 interrupt*/
.long Reserved90_IRQHandler /* Reserved Interrupt 90*/
.long Reserved91_IRQHandler /* Reserved Interrupt 91*/
.long Reserved92_IRQHandler /* Reserved Interrupt 92*/
.long Reserved93_IRQHandler /* Reserved Interrupt 93*/
.long Reserved94_IRQHandler /* Reserved Interrupt 94*/
.long Reserved95_IRQHandler /* Reserved Interrupt 95*/
.long Reserved96_IRQHandler /* Reserved Interrupt 96*/
.long Reserved97_IRQHandler /* Reserved Interrupt 97*/
.long Reserved98_IRQHandler /* Reserved Interrupt 98*/
.long Reserved99_IRQHandler /* Reserved Interrupt 99*/
.long Reserved100_IRQHandler /* Reserved Interrupt 100*/
.long Reserved101_IRQHandler /* Reserved Interrupt 101*/
.size __isr_vector, . - __isr_vector
.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. */
disable_watchdog:
/* unlock */
ldr r1, =0x4005200e
ldr r0, =0xc520
strh r0, [r1]
ldr r0, =0xd928
strh r0, [r1]
/* disable */
ldr r1, =0x40052000
ldr r0, =0x01d2
strh r0, [r1]
ldr r1, =__etext
ldr r2, =__data_start__
ldr r3, =__data_end__
subs r3, r2
ble .Lflash_to_ram_loop_end
movs r4, 0
.Lflash_to_ram_loop:
ldr r0, [r1,r4]
str r0, [r2,r4]
adds r4, 4
cmp r4, r3
blt .Lflash_to_ram_loop
.Lflash_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
/* Exception Handlers */
def_default_handler NMI_Handler
def_default_handler HardFault_Handler
def_default_handler MemManage_Handler
def_default_handler BusFault_Handler
def_default_handler UsageFault_Handler
def_default_handler SVC_Handler
def_default_handler DebugMon_Handler
def_default_handler PendSV_Handler
def_default_handler SysTick_Handler
def_default_handler Default_Handler
.macro def_irq_default_handler handler_name
.weak \handler_name
.set \handler_name, Default_Handler
.endm
/* IRQ Handlers */
def_irq_default_handler DMA0_IRQHandler
def_irq_default_handler DMA1_IRQHandler
def_irq_default_handler DMA2_IRQHandler
def_irq_default_handler DMA3_IRQHandler
def_irq_default_handler DMA4_IRQHandler
def_irq_default_handler DMA5_IRQHandler
def_irq_default_handler DMA6_IRQHandler
def_irq_default_handler DMA7_IRQHandler
def_irq_default_handler DMA8_IRQHandler
def_irq_default_handler DMA9_IRQHandler
def_irq_default_handler DMA10_IRQHandler
def_irq_default_handler DMA11_IRQHandler
def_irq_default_handler DMA12_IRQHandler
def_irq_default_handler DMA13_IRQHandler
def_irq_default_handler DMA14_IRQHandler
def_irq_default_handler DMA15_IRQHandler
def_irq_default_handler DMA_Error_IRQHandler
def_irq_default_handler MCM_IRQHandler
def_irq_default_handler FTF_IRQHandler
def_irq_default_handler Read_Collision_IRQHandler
def_irq_default_handler LVD_LVW_IRQHandler
def_irq_default_handler LLW_IRQHandler
def_irq_default_handler Watchdog_IRQHandler
def_irq_default_handler RNG_IRQHandler
def_irq_default_handler I2C0_IRQHandler
def_irq_default_handler I2C1_IRQHandler
def_irq_default_handler SPI0_IRQHandler
def_irq_default_handler SPI1_IRQHandler
def_irq_default_handler I2S0_Tx_IRQHandler
def_irq_default_handler I2S0_Rx_IRQHandler
def_irq_default_handler LPUART0_IRQHandler
def_irq_default_handler UART0_RX_TX_IRQHandler
def_irq_default_handler UART0_ERR_IRQHandler
def_irq_default_handler UART1_RX_TX_IRQHandler
def_irq_default_handler UART1_ERR_IRQHandler
def_irq_default_handler UART2_RX_TX_IRQHandler
def_irq_default_handler UART2_ERR_IRQHandler
def_irq_default_handler Reserved53_IRQHandler
def_irq_default_handler Reserved54_IRQHandler
def_irq_default_handler ADC0_IRQHandler
def_irq_default_handler CMP0_IRQHandler
def_irq_default_handler CMP1_IRQHandler
def_irq_default_handler FTM0_IRQHandler
def_irq_default_handler FTM1_IRQHandler
def_irq_default_handler FTM2_IRQHandler
def_irq_default_handler Reserved61_IRQHandler
def_irq_default_handler RTC_IRQHandler
def_irq_default_handler RTC_Seconds_IRQHandler
def_irq_default_handler PIT0_IRQHandler
def_irq_default_handler PIT1_IRQHandler
def_irq_default_handler PIT2_IRQHandler
def_irq_default_handler PIT3_IRQHandler
def_irq_default_handler PDB0_IRQHandler
def_irq_default_handler USB0_IRQHandler
def_irq_default_handler Reserved70_IRQHandler
def_irq_default_handler Reserved71_IRQHandler
def_irq_default_handler DAC0_IRQHandler
def_irq_default_handler MCG_IRQHandler
def_irq_default_handler LPTimer_IRQHandler
def_irq_default_handler PORTA_IRQHandler
def_irq_default_handler PORTB_IRQHandler
def_irq_default_handler PORTC_IRQHandler
def_irq_default_handler PORTD_IRQHandler
def_irq_default_handler PORTE_IRQHandler
def_irq_default_handler SWI_IRQHandler
def_irq_default_handler Reserved81_IRQHandler
def_irq_default_handler Reserved82_IRQHandler
def_irq_default_handler Reserved83_IRQHandler
def_irq_default_handler Reserved84_IRQHandler
def_irq_default_handler Reserved85_IRQHandler
def_irq_default_handler Reserved86_IRQHandler
def_irq_default_handler FTM3_IRQHandler
def_irq_default_handler DAC1_IRQHandler
def_irq_default_handler ADC1_IRQHandler
def_irq_default_handler Reserved90_IRQHandler
def_irq_default_handler Reserved91_IRQHandler
def_irq_default_handler Reserved92_IRQHandler
def_irq_default_handler Reserved93_IRQHandler
def_irq_default_handler Reserved94_IRQHandler
def_irq_default_handler Reserved95_IRQHandler
def_irq_default_handler Reserved96_IRQHandler
def_irq_default_handler Reserved97_IRQHandler
def_irq_default_handler Reserved98_IRQHandler
def_irq_default_handler Reserved99_IRQHandler
def_irq_default_handler Reserved100_IRQHandler
def_irq_default_handler Reserved101_IRQHandler
def_irq_default_handler DefaultISR
/* Flash protection region, placed at 0x400 */
.text
.thumb
.align 2
.section .kinetis_flash_config_field,"a",%progbits
kinetis_flash_config:
.long 0xffffffff
.long 0xffffffff
.long 0xffffffff
.long 0xfffffffe
.end

View File

@ -1,120 +0,0 @@
/*
* Copyright (c) 2013 - 2014, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o 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.
*
* o Neither the name of Freescale Semiconductor, Inc. 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 THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include <assert.h>
#include "fsl_interrupt_manager.h"
/*******************************************************************************
* Definitions
******************************************************************************/
/*!
* @brief Counter to manage the nested callings of global disable/enable interrupt.
*/
uint32_t g_interruptDisableCount = 0;
/*******************************************************************************
* Code
******************************************************************************/
/*FUNCTION**********************************************************************
*
* Function Name : INT_SYS_InstallHandler
* Description : Install an interrupt handler routine for a given IRQ number
* This function will let application to register/replace the interrupt
* handler for specified IRQ number. IRQ number is different with Vector
* number. IRQ 0 will start from Vector 16 address. Refer to reference
* manual for details. Also refer to startup_MKxxxx.s file for each chip
* family to find out the default interrut handler for each device. This
* function will convert the IRQ number to vector number by adding 16 to
* it.
*
*END**************************************************************************/
void INT_SYS_InstallHandler(IRQn_Type irqNumber, void (*handler)(void))
{
#if (defined(KEIL))
extern uint32_t Image$$VECTOR_RAM$$Base[];
#define __VECTOR_RAM Image$$VECTOR_RAM$$Base
#else
extern uint32_t __VECTOR_RAM[];
#endif
/* check IRQ number */
assert(FSL_FEATURE_INTERRUPT_IRQ_MIN <= irqNumber);
assert(irqNumber <= FSL_FEATURE_INTERRUPT_IRQ_MAX);
/* set handler into vector table*/
__VECTOR_RAM[irqNumber + 16] = (uint32_t)handler;
}
/*FUNCTION**********************************************************************
*
* Function Name : INT_SYS_EnableIRQGlobal
* Description : Enable system interrupt
* This function will enable the global interrupt by calling the core API
*
*END**************************************************************************/
void INT_SYS_EnableIRQGlobal(void)
{
/* check and update */
if (g_interruptDisableCount > 0)
{
g_interruptDisableCount--;
if (g_interruptDisableCount > 0)
{
return;
}
/* call core API to enable the global interrupt*/
__enable_irq();
}
}
/*FUNCTION**********************************************************************
*
* Function Name : INT_SYS_DisableIRQGlobal
* Description : Disnable system interrupt
* This function will disable the global interrupt by calling the core API
*
*END**************************************************************************/
void INT_SYS_DisableIRQGlobal(void)
{
/* call core API to disable the global interrupt*/
__disable_irq();
/* update counter*/
g_interruptDisableCount++;
}
/*******************************************************************************
* EOF
******************************************************************************/

View File

@ -1,311 +0,0 @@
/*
* Copyright (c) 2013 - 2014, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o 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.
*
* o Neither the name of Freescale Semiconductor, Inc. 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 THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/*************************************************************************************************
* Includes Section
************************************************************************************************/
#include "sw_timer.h"
#include "fsl_interrupt_manager.h"
#include "fsl_clock_manager.h"
#include "fsl_pit_driver.h"
/*************************************************************************************************
* Defines & Macros Section
************************************************************************************************/
#ifndef SW_TIMER_NUMBER_CHANNELS
/*! Number of channels to be used as timers. The maximum value of channels supported is 32.*/
#define SW_TIMER_NUMBER_CHANNELS (32)
/*! Defines the count unit in ms of the software timer.*/
#define SW_TIMER_COUNT_UNIT_MS (1)
#endif
/*! Return if the timer channel is reserved.*/
#define IS_TIMER_CHANNEL_RESERVED(chann) (gs_areChannelsEnabled & (channel_enabler_t)(1 << chann))
/*************************************************************************************************
* Typedef Section
************************************************************************************************/
#if (SW_TIMER_NUMBER_CHANNELS <= 8)
/*! Defines the size of variable that stores "enable" flags of each channel.*/
typedef uint8_t channel_enabler_t;
#else
#if (SW_TIMER_NUMBER_CHANNELS <= 16)
/*! Defines the size of variable that stores "enable" flags of each channel.*/
typedef uint16_t channel_enabler_t;
#else
#if (SW_TIMER_NUMBER_CHANNELS <= 32)
/*! Defines the size of variable that stores "enable" flags of each channel.*/
typedef uint32_t channel_enabler_t;
#else
#error "Cannot handle more than 32 auxiliary software timer channels."
#endif
#endif
#endif
/*************************************************************************************************
* Global Constants Section
************************************************************************************************/
/*************************************************************************************************
* Static Constants Section
************************************************************************************************/
/** Constant to select the PIT timer channel to use for timebase. Channels 0 and 1 have special
* hardware trigger capabilities, so they should be avoided.
*/
static const uint8_t kSWTimerPITChannel = FSL_FEATURE_PIT_TIMER_COUNT - 1;
/*************************************************************************************************
* Global Variables Section
************************************************************************************************/
/*************************************************************************************************
* Static Variables Section
************************************************************************************************/
/*! Free running counter that everyone can read.*/
static volatile time_free_counter_t gs_freeCounter;
/*! Independent counters of software timer module. A counter is defined for every channel.*/
static volatile time_counter_t gs_channelCounters[SW_TIMER_NUMBER_CHANNELS];
/*! Variable used to indicate which channels are enabled. Bit 0 corresponds to channel 0, bit 1 to*/
/*! channel 1, etc.*/
static volatile channel_enabler_t gs_areChannelsEnabled;
/*************************************************************************************************
* Functions Section
************************************************************************************************/
/* See sw_timer.h for documentation of this function.*/
uint32_t sw_timer_init_service(void)
{
pit_user_config_t pitConfig;
/* All channels are disabled*/
gs_areChannelsEnabled = 0;
/* Init free running counter*/
gs_freeCounter = 0;
/* Define PIT channel init structure. */
pitConfig.isInterruptEnabled = true;
pitConfig.isTimerChained = false;
pitConfig.periodUs = 1000;/* Set 1ms period */
/* Init PIT module and enable all timers run in debug mode.*/
pit_init_module(true);
/* Init PIT channel. */
pit_init_channel(kSWTimerPITChannel, &pitConfig);
/* Register PIT callback function.*/
pit_register_isr_callback_function(kSWTimerPITChannel, sw_timer_update_counters);
/* Start timer counting. */
pit_timer_start(kSWTimerPITChannel);
return kSwTimerStatusSuccess;
}
/* See sw_timer.h for documentation of this function.*/
void sw_timer_shutdown_service(void)
{
pit_shutdown();
}
/* See sw_timer.h for documentation of this function.*/
uint8_t sw_timer_reserve_channel(void)
{
static uint8_t lastFreeChannel = 0;
uint8_t searchIndex;
uint8_t newReservedChannel;
/* Initialize search index with the last free channel to search faster for a free channel*/
searchIndex = lastFreeChannel;
/* Not channel available by default*/
newReservedChannel = kSwTimerChannelNotAvailable;
/* Searching for a free channel*/
do {
/* The channel is free*/
if(!IS_TIMER_CHANNEL_RESERVED(searchIndex))
{
/* Set channel as reserved*/
newReservedChannel = searchIndex;
gs_areChannelsEnabled |= (1u << newReservedChannel);
/* Update last free channel with the next channel*/
lastFreeChannel = newReservedChannel + 1;
/* Flag of the last channel has been checked and need to start over with channel 0*/
if (lastFreeChannel == SW_TIMER_NUMBER_CHANNELS)
{
lastFreeChannel = 0;
}
}
/* The channel is already reserved*/
else
{
searchIndex = (searchIndex + 1) % SW_TIMER_NUMBER_CHANNELS;
}
}while((searchIndex != lastFreeChannel) &&
(kSwTimerChannelNotAvailable == newReservedChannel));
return newReservedChannel;
}
/* See sw_timer.h for documentation of this function.*/
sw_timer_channel_status_t sw_timer_get_channel_status(uint8_t timerChannel)
{
sw_timer_channel_status_t channelStatus;
/* Is it a valid channel?*/
if(SW_TIMER_NUMBER_CHANNELS > timerChannel)
{
/* The channel is reserved*/
if(IS_TIMER_CHANNEL_RESERVED(timerChannel))
{
/* The timeout has expired*/
if(0 >= gs_channelCounters[timerChannel])
{
channelStatus = kSwTimerChannelExpired;
}
/* The counter is still counting*/
else
{
channelStatus = kSwTimerChannelStillCounting;
}
}
/* The channel is not reserved*/
else
{
channelStatus = kSwTimerChannelIsDisable;
}
}
/* The channel is not valid*/
else
{
channelStatus = kSwTimerChannelNotAvailable;
}
return channelStatus;
}
/* See sw_timer.h for documentation of this function.*/
uint32_t sw_timer_start_channel(uint8_t timerChannel, time_counter_t timeout)
{
uint32_t startStatus;
/* Is it a valid channel?*/
if(SW_TIMER_NUMBER_CHANNELS > timerChannel)
{
/* Set the given timeout in the corresponding channel counter. The timeout should be a */
/* multiple of SW_TIMER_COUNT_UNIT_MS, otherwise it will be taken the integer part of the */
/* division.*/
gs_channelCounters[timerChannel] = timeout / SW_TIMER_COUNT_UNIT_MS;
startStatus = kSwTimerStatusSuccess;
}
else
{
startStatus = kSwTimerStatusInvalidChannel;
}
return startStatus;
}
/* See sw_timer.h for documentation of this function.*/
uint32_t sw_timer_release_channel(uint8_t timerChannel)
{
uint32_t releaseStatus;
/* Is it a valid channel?*/
if(SW_TIMER_NUMBER_CHANNELS > timerChannel)
{
/* Set channel as disable*/
gs_areChannelsEnabled &= (~(1u << timerChannel));
releaseStatus = kSwTimerStatusSuccess;
}
else
{
releaseStatus = kSwTimerStatusInvalidChannel;
}
return releaseStatus;
}
/* See sw_timer.h for documentation of this function.*/
time_free_counter_t sw_timer_get_free_counter(void)
{
return gs_freeCounter;
}
/* See sw_timer.h for documentation of this function.*/
void sw_timer_update_counters(void)
{
uint8_t index;
index = SW_TIMER_NUMBER_CHANNELS;
do {
--index;
/* Decrement all counters. To determine if the timeout has expired call */
--gs_channelCounters[index];
} while(0 != index);
/* Increment free running counter*/
++gs_freeCounter;
}
/*******************************************************************************
* EOF
******************************************************************************/

View File

@ -53,6 +53,7 @@ extern "C" {
#define STM_MODE_EVT_RISING (9)
#define STM_MODE_EVT_FALLING (10)
#define STM_MODE_EVT_RISING_FALLING (11)
#define STM_MODE_IT_EVT_RESET (12)
// High nibble = port number (0=A, 1=B, 2=C, 3=D, 4=E, 5=F, 6=G, 7=H)
// Low nibble = pin number

View File

@ -222,7 +222,29 @@ void gpio_irq_set(gpio_irq_t *obj, gpio_irq_event event, uint32_t enable) {
} else {
mode = STM_MODE_INPUT;
pull = GPIO_NOPULL;
obj->event = EDGE_NONE;
if (event == IRQ_RISE) {
if ((obj->event == EDGE_FALL) || (obj->event == EDGE_BOTH)) {
mode = STM_MODE_IT_FALLING;
obj->event = EDGE_FALL;
} else if (obj->event == EDGE_RISE) {
mode = STM_MODE_IT_EVT_RESET;
obj->event = EDGE_NONE;
}
}
else if (event == IRQ_FALL) {
if ((obj->event == EDGE_RISE) || (obj->event == EDGE_BOTH)) {
mode = STM_MODE_IT_RISING;
obj->event = EDGE_RISE;
} else if (obj->event == IRQ_FALL) {
mode = STM_MODE_IT_EVT_RESET;
obj->event = EDGE_NONE;
}
}
else {
mode = STM_MODE_IT_EVT_RESET;
obj->event = EDGE_NONE;
}
}
pin_function(obj->pin, STM_PIN_DATA(mode, pull, 0));

View File

@ -33,7 +33,7 @@
#include "mbed_error.h"
// GPIO mode look-up table
static const uint32_t gpio_mode[12] = {
static const uint32_t gpio_mode[13] = {
0x00000000, // 0 = GPIO_MODE_INPUT
0x00000001, // 1 = GPIO_MODE_OUTPUT_PP
0x00000011, // 2 = GPIO_MODE_OUTPUT_OD
@ -45,7 +45,8 @@ static const uint32_t gpio_mode[12] = {
0x10310000, // 8 = GPIO_MODE_IT_RISING_FALLING
0x10120000, // 9 = GPIO_MODE_EVT_RISING
0x10220000, // 10 = GPIO_MODE_EVT_FALLING
0x10320000 // 11 = GPIO_MODE_EVT_RISING_FALLING
0x10320000, // 11 = GPIO_MODE_EVT_RISING_FALLING
0x10000000 // 12 = Reset GPIO_MODE_IT_EVT
};
// Enable GPIO clock and return GPIO base address

View File

@ -53,6 +53,7 @@ extern "C" {
#define STM_MODE_EVT_RISING (9)
#define STM_MODE_EVT_FALLING (10)
#define STM_MODE_EVT_RISING_FALLING (11)
#define STM_MODE_IT_EVT_RESET (12)
// High nibble = port number (0=A, 1=B, 2=C, 3=D, 4=E, 5=F, 6=G, 7=H)
// Low nibble = pin number

View File

@ -233,7 +233,28 @@ void gpio_irq_set(gpio_irq_t *obj, gpio_irq_event event, uint32_t enable)
} else {
mode = STM_MODE_INPUT;
pull = GPIO_NOPULL;
obj->event = EDGE_NONE;
if (event == IRQ_RISE) {
if ((obj->event == EDGE_FALL) || (obj->event == EDGE_BOTH)) {
mode = STM_MODE_IT_FALLING;
obj->event = EDGE_FALL;
} else if (obj->event == EDGE_RISE) {
mode = STM_MODE_IT_EVT_RESET;
obj->event = EDGE_NONE;
}
}
else if (event == IRQ_FALL) {
if ((obj->event == EDGE_RISE) || (obj->event == EDGE_BOTH)) {
mode = STM_MODE_IT_RISING;
obj->event = EDGE_RISE;
} else if (obj->event == IRQ_FALL) {
mode = STM_MODE_IT_EVT_RESET;
obj->event = EDGE_NONE;
}
}
else {
mode = STM_MODE_IT_EVT_RESET;
obj->event = EDGE_NONE;
}
}
pin_function(obj->pin, STM_PIN_DATA(mode, pull, 0));

View File

@ -33,7 +33,7 @@
#include "mbed_error.h"
// GPIO mode look-up table
static const uint32_t gpio_mode[12] = {
static const uint32_t gpio_mode[13] = {
0x00000000, // 0 = GPIO_MODE_INPUT
0x00000001, // 1 = GPIO_MODE_OUTPUT_PP
0x00000011, // 2 = GPIO_MODE_OUTPUT_OD
@ -45,7 +45,8 @@ static const uint32_t gpio_mode[12] = {
0x10310000, // 8 = GPIO_MODE_IT_RISING_FALLING
0x10120000, // 9 = GPIO_MODE_EVT_RISING
0x10220000, // 10 = GPIO_MODE_EVT_FALLING
0x10320000 // 11 = GPIO_MODE_EVT_RISING_FALLING
0x10320000, // 11 = GPIO_MODE_EVT_RISING_FALLING
0x10000000 // 12 = Reset GPIO_MODE_IT_EVT
};
// Enable GPIO clock and return GPIO base address

View File

@ -53,6 +53,7 @@ extern "C" {
#define STM_MODE_EVT_RISING (9)
#define STM_MODE_EVT_FALLING (10)
#define STM_MODE_EVT_RISING_FALLING (11)
#define STM_MODE_IT_EVT_RESET (12)
// High nibble = port number (0=A, 1=B, 2=C, 3=D, 4=E, 5=F, 6=G, 7=H)
// Low nibble = pin number

View File

@ -223,7 +223,28 @@ void gpio_irq_set(gpio_irq_t *obj, gpio_irq_event event, uint32_t enable) {
} else {
mode = STM_MODE_INPUT;
pull = GPIO_NOPULL;
obj->event = EDGE_NONE;
if (event == IRQ_RISE) {
if ((obj->event == EDGE_FALL) || (obj->event == EDGE_BOTH)) {
mode = STM_MODE_IT_FALLING;
obj->event = EDGE_FALL;
} else if (obj->event == EDGE_RISE) {
mode = STM_MODE_IT_EVT_RESET;
obj->event = EDGE_NONE;
}
}
else if (event == IRQ_FALL) {
if ((obj->event == EDGE_RISE) || (obj->event == EDGE_BOTH)) {
mode = STM_MODE_IT_RISING;
obj->event = EDGE_RISE;
} else if (obj->event == IRQ_FALL) {
mode = STM_MODE_IT_EVT_RESET;
obj->event = EDGE_NONE;
}
}
else {
mode = STM_MODE_IT_EVT_RESET;
obj->event = EDGE_NONE;
}
}
pin_function(obj->pin, STM_PIN_DATA(mode, pull, 0));

View File

@ -33,7 +33,7 @@
#include "mbed_error.h"
// GPIO mode look-up table
static const uint32_t gpio_mode[12] = {
static const uint32_t gpio_mode[13] = {
0x00000000, // 0 = GPIO_MODE_INPUT
0x00000001, // 1 = GPIO_MODE_OUTPUT_PP
0x00000011, // 2 = GPIO_MODE_OUTPUT_OD
@ -45,7 +45,8 @@ static const uint32_t gpio_mode[12] = {
0x10310000, // 8 = GPIO_MODE_IT_RISING_FALLING
0x10120000, // 9 = GPIO_MODE_EVT_RISING
0x10220000, // 10 = GPIO_MODE_EVT_FALLING
0x10320000 // 11 = GPIO_MODE_EVT_RISING_FALLING
0x10320000, // 11 = GPIO_MODE_EVT_RISING_FALLING
0x10000000 // 12 = Reset GPIO_MODE_IT_EVT
};
// Enable GPIO clock and return GPIO base address

View File

@ -0,0 +1,472 @@
/*
* Copyright (c) 2013 - 2014, Freescale Semiconductor, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* o Redistributions of source code must retain the above copyright notice, this list
* of conditions and the following disclaimer.
*
* o 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.
*
* o Neither the name of Freescale Semiconductor, Inc. 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 THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
* ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
/* Modified by mbed for the lwIP port */
#include "fsl_enet_driver.h"
#include "fsl_enet_hal.h"
#include "fsl_clock_manager.h"
#include "fsl_interrupt_manager.h"
#include <string.h>
#include "sys_arch.h"
/*******************************************************************************
* Variables
******************************************************************************/
/*! @brief Define ENET's IRQ list */
void *enetIfHandle;
/*! @brief Define MAC driver API structure and for application of stack adaptor layer*/
const enet_mac_api_t g_enetMacApi =
{
enet_mac_init,
NULL, // enet_mac_deinit,
NULL, // enet_mac_send,
#if !ENET_RECEIVE_ALL_INTERRUPT
NULL, // enet_mac_receive,
#endif
enet_mii_read,
enet_mii_write,
NULL, // enet_mac_add_multicast_group,
NULL, //enet_mac_leave_multicast_group,
};
/*******************************************************************************
* Code
******************************************************************************/
// NOTE: we need these functions to be non-blocking fpr the PHY task, hence the
// osDelay() below
/*FUNCTION****************************************************************
*
* Function Name: enet_mii_read
* Return Value: The execution status.
* Description: Read function.
* This interface read data over the (R)MII bus from the specified PHY register,
* This function is called by all PHY interfaces.
*END*********************************************************************/
uint32_t enet_mii_read(uint32_t instance, uint32_t phyAddr, uint32_t phyReg, uint32_t *dataPtr)
{
uint32_t counter;
/* Check the input parameters*/
if (!dataPtr)
{
return kStatus_ENET_InvalidInput;
}
/* Check if the mii is enabled*/
if (!enet_hal_is_mii_enabled(instance))
{
return kStatus_ENET_Miiuninitialized;
}
/* Clear the MII interrupt event*/
enet_hal_clear_interrupt(instance, kEnetMiiInterrupt);
/* Read command operation*/
enet_hal_set_mii_command(instance, phyAddr, phyReg, kEnetReadValidFrame, 0);
/* Poll for MII complete*/
for (counter = 0; counter < kEnetMaxTimeout; counter++)
{
if (enet_hal_get_interrupt_status(instance, kEnetMiiInterrupt))
{
break;
}
osDelay(1);
}
/* Check for timeout*/
if (counter == kEnetMaxTimeout)
{
return kStatus_ENET_TimeOut;
}
/* Get data from mii register*/
*dataPtr = enet_hal_get_mii_data(instance);
/* Clear MII interrupt event*/
enet_hal_clear_interrupt(instance, kEnetMiiInterrupt);
return kStatus_ENET_Success;
}
/*FUNCTION****************************************************************
*
* Function Name: enet_mii_write
* Return Value: The execution status.
* Description: Write function.
* This interface write data over the (R)MII bus to the specified PHY register.
* This function is called by all PHY interfaces.
*END*********************************************************************/
uint32_t enet_mii_write(uint32_t instance, uint32_t phyAddr, uint32_t phyReg, uint32_t data)
{
uint32_t counter;
/* Check if the mii is enabled*/
if (!enet_hal_is_mii_enabled(instance))
{
return kStatus_ENET_Miiuninitialized;
}
/* Clear the MII interrupt event*/
enet_hal_clear_interrupt(instance, kEnetMiiInterrupt);
/* Read command operation*/
enet_hal_set_mii_command(instance, phyAddr, phyReg, kEnetWriteValidFrame, data);
/* Poll for MII complete*/
for (counter = 0; counter < kEnetMaxTimeout; counter++)
{
if (enet_hal_get_interrupt_status(instance, kEnetMiiInterrupt))
{
break;
}
osDelay(1);
}
/* Check for timeout*/
if (counter == kEnetMaxTimeout)
{
return kStatus_ENET_TimeOut;
}
/* Clear MII intrrupt event*/
enet_hal_clear_interrupt(instance, kEnetMiiInterrupt);
return kStatus_ENET_Success;
}
/*FUNCTION****************************************************************
*
* Function Name: enet_mac_mii_init
* Return Value: The execution status.
* Description:Initialize the ENET Mac mii(mdc/mdio)interface.
*END*********************************************************************/
uint32_t enet_mac_mii_init(enet_dev_if_t * enetIfPtr)
{
uint32_t frequency;
/* Check the input parameters*/
if (enetIfPtr == NULL)
{
return kStatus_ENET_InvalidInput;
}
/* Configure mii speed*/
CLOCK_SYS_GetFreq(kSystemClock, &frequency);
enet_hal_config_mii(enetIfPtr->deviceNumber, (frequency/(2 * enetIfPtr->macCfgPtr->miiClock) + 1),
kEnetMdioHoldOneClkCycle, false);
return kStatus_ENET_Success;
}
/*FUNCTION****************************************************************
*
* Function Name: enet_mac_rxbd_init
* Return Value: The execution status.
* Description:Initialize the ENET receive buffer descriptors.
* Note: If you do receive on receive interrupt handler the receive
* data buffer number can be the same as the receive descriptor numbers.
* But if you are polling receive frames please make sure the receive data
* buffers are more than buffer descriptors to guarantee a good performance.
*END*********************************************************************/
uint32_t enet_mac_rxbd_init(enet_dev_if_t * enetIfPtr, enet_rxbd_config_t *rxbdCfg)
{
/* Check the input parameters*/
if ((!enetIfPtr) || (!rxbdCfg))
{
return kStatus_ENET_InvalidInput;
}
enetIfPtr->macContextPtr->bufferdescSize = enet_hal_get_bd_size();
/* Initialize the bd status*/
enetIfPtr->macContextPtr->isRxFull = false;
/* Initialize receive bd base address and current address*/
enetIfPtr->macContextPtr->rxBdBasePtr = rxbdCfg->rxBdPtrAlign;
enetIfPtr->macContextPtr->rxBdCurPtr = enetIfPtr->macContextPtr->rxBdBasePtr;
enetIfPtr->macContextPtr->rxBdDirtyPtr = enetIfPtr->macContextPtr->rxBdBasePtr;
enet_hal_set_rxbd_address(enetIfPtr->deviceNumber, (uint32_t)(enetIfPtr->macContextPtr->rxBdBasePtr));
return kStatus_ENET_Success;
}
/*FUNCTION****************************************************************
*
* Function Name: enet_mac_txbd_init
* Return Value: The execution status.
* Description:Initialize the ENET transmit buffer descriptors.
* This function prepare all of the transmit buffer descriptors.
*END*********************************************************************/
uint32_t enet_mac_txbd_init(enet_dev_if_t * enetIfPtr, enet_txbd_config_t *txbdCfg)
{
/* Check the input parameters*/
if ((!enetIfPtr) || (!txbdCfg))
{
return kStatus_ENET_InvalidInput;
}
/* Initialize the bd status*/
enetIfPtr->macContextPtr->isTxFull = false;
/* Initialize transmit bd base address and current address*/
enetIfPtr->macContextPtr->txBdBasePtr = txbdCfg->txBdPtrAlign;
enetIfPtr->macContextPtr->txBdCurPtr = enetIfPtr->macContextPtr->txBdBasePtr;
enetIfPtr->macContextPtr->txBdDirtyPtr = enetIfPtr->macContextPtr->txBdBasePtr;
enet_hal_set_txbd_address(enetIfPtr->deviceNumber, (uint32_t)(enetIfPtr->macContextPtr->txBdBasePtr));
return kStatus_ENET_Success;
}
/*FUNCTION****************************************************************
*
* Function Name: enet_mac_configure_fifo_accel
* Return Value: The execution status.
* Description: Configure the ENET FIFO and Accelerator.
*END*********************************************************************/
uint32_t enet_mac_configure_fifo_accel(enet_dev_if_t * enetIfPtr)
{
enet_config_rx_fifo_t rxFifo;
enet_config_tx_fifo_t txFifo;
/* Check the input parameters*/
if (!enetIfPtr)
{
return kStatus_ENET_InvalidInput;
}
/* Initialize values that will not be initialized later on */
rxFifo.rxEmpty = 0;
rxFifo.rxFull = 0;
txFifo.isStoreForwardEnabled = 0;
txFifo.txFifoWrite = 0;
txFifo.txEmpty = 0;
/* Configure tx/rx accelerator*/
if (enetIfPtr->macCfgPtr->isRxAccelEnabled)
{
enet_hal_config_rx_accelerator(enetIfPtr->deviceNumber,
(enet_config_rx_accelerator_t *)&(enetIfPtr->macCfgPtr->rxAcceler));
if ((enetIfPtr->macCfgPtr->rxAcceler.isIpcheckEnabled) || (enetIfPtr->macCfgPtr->rxAcceler.isProtocolCheckEnabled))
{
rxFifo.rxFull = 0;
}
}
if (enetIfPtr->macCfgPtr->isTxAccelEnabled)
{
enet_hal_config_tx_accelerator(enetIfPtr->deviceNumber,
(enet_config_tx_accelerator_t *)&(enetIfPtr->macCfgPtr->txAcceler));
if ((enetIfPtr->macCfgPtr->txAcceler.isIpCheckEnabled) || (enetIfPtr->macCfgPtr->txAcceler.isProtocolCheckEnabled))
{
txFifo.isStoreForwardEnabled = 1;
}
}
if (enetIfPtr->macCfgPtr->isStoreAndFwEnabled)
{
rxFifo.rxFull = 0;
txFifo.isStoreForwardEnabled = 1;
}
/* Set TFWR value if STRFWD is not being used */
if (txFifo.isStoreForwardEnabled == 1)
txFifo.txFifoWrite = 0;
else
/* TFWR value is a trade-off between transmit latency and risk of transmit FIFO underrun due to contention for the system bus
TFWR = 15 means transmission will begin once 960 bytes has been written to the Tx FIFO (for frames larger than 960 bytes)
See Section 45.4.18 - Transmit FIFO Watermark Register of the K64F Reference Manual for details */
txFifo.txFifoWrite = 15;
/* Configure tx/rx FIFO with default value*/
rxFifo.rxAlmostEmpty = 4;
rxFifo.rxAlmostFull = 4;
txFifo.txAlmostEmpty = 4;
txFifo.txAlmostFull = 8;
enet_hal_config_rx_fifo(enetIfPtr->deviceNumber, &rxFifo);
enet_hal_config_tx_fifo(enetIfPtr->deviceNumber, &txFifo);
return kStatus_ENET_Success;
}
/*FUNCTION****************************************************************
*
* Function Name: enet_mac_configure_controller
* Return Value: The execution status.
* Description: Configure the ENET controller with the basic configuration.
*END*********************************************************************/
uint32_t enet_mac_configure_controller(enet_dev_if_t * enetIfPtr)
{
uint32_t macCtlCfg;
/* Check the input parameters*/
if (enetIfPtr == NULL)
{
return kStatus_ENET_InvalidInput;
}
macCtlCfg = enetIfPtr->macCfgPtr->macCtlConfigure;
/* Configure rmii/mii interface*/
enet_hal_config_rmii(enetIfPtr->deviceNumber, enetIfPtr->macCfgPtr->rmiiCfgMode,
enetIfPtr->macCfgPtr->speed, enetIfPtr->macCfgPtr->duplex, false,
(macCtlCfg & kEnetRxMiiLoopback));
/* Configure receive buffer size*/
if (enetIfPtr->macCfgPtr->isVlanEnabled)
{
enetIfPtr->maxFrameSize = kEnetMaxFrameVlanSize;
enet_hal_set_rx_max_size(enetIfPtr->deviceNumber,
enetIfPtr->macContextPtr->rxBufferSizeAligned, kEnetMaxFrameVlanSize);
}
else
{
enetIfPtr->maxFrameSize = kEnetMaxFrameSize;
enet_hal_set_rx_max_size(enetIfPtr->deviceNumber,
enetIfPtr->macContextPtr->rxBufferSizeAligned, kEnetMaxFrameSize);
}
/* Set receive controller promiscuous */
enet_hal_config_promiscuous(enetIfPtr->deviceNumber, macCtlCfg & kEnetRxPromiscuousEnable);
/* Set receive flow control*/
enet_hal_enable_flowcontrol(enetIfPtr->deviceNumber, (macCtlCfg & kEnetRxFlowControlEnable));
/* Set received PAUSE frames are forwarded/terminated*/
enet_hal_enable_pauseforward(enetIfPtr->deviceNumber, (macCtlCfg & kEnetRxPauseFwdEnable));
/* Set receive broadcast frame reject*/
enet_hal_enable_broadcastreject(enetIfPtr->deviceNumber, (macCtlCfg & kEnetRxBcRejectEnable));
/* Set padding is removed from the received frame*/
enet_hal_enable_padremove(enetIfPtr->deviceNumber, (macCtlCfg & kEnetRxPadRemoveEnable));
/* Set the crc of the received frame is stripped from the frame*/
enet_hal_enable_rxcrcforward(enetIfPtr->deviceNumber, (macCtlCfg & kEnetRxCrcFwdEnable));
/* Set receive payload length check*/
enet_hal_enable_payloadcheck(enetIfPtr->deviceNumber, (macCtlCfg & kEnetPayloadlenCheckEnable));
/* Set control sleep mode*/
enet_hal_enable_sleep(enetIfPtr->deviceNumber, (macCtlCfg & kEnetSleepModeEnable));
return kStatus_ENET_Success;
}
/*FUNCTION****************************************************************
*
* Function Name: enet_mac_init
* Return Value: The execution status.
* Description:Initialize the ENET device with the basic configuration
* When ENET is used, this function need to be called by the NET initialize
* interface.
*END*********************************************************************/
uint32_t enet_mac_init(enet_dev_if_t * enetIfPtr, enet_rxbd_config_t *rxbdCfg,
enet_txbd_config_t *txbdCfg)
{
uint32_t timeOut = 0;
uint32_t devNumber, result = 0;
/* Check the input parameters*/
if (enetIfPtr == NULL)
{
return kStatus_ENET_InvalidInput;
}
/* Get device number and check the parameter*/
devNumber = enetIfPtr->deviceNumber;
/* Store the global ENET structure for ISR input parameters for instance 0*/
if (!devNumber)
{
enetIfHandle = enetIfPtr;
}
/* Turn on ENET module clock gate */
CLOCK_SYS_EnableEnetClock(0U);
/* Reset ENET mac*/
enet_hal_reset_ethernet(devNumber);
while ((!enet_hal_is_reset_completed(devNumber)) && (timeOut < kEnetMaxTimeout))
{
time_delay(1);
timeOut++;
}
/* Check out if timeout*/
if (timeOut == kEnetMaxTimeout)
{
return kStatus_ENET_TimeOut;
}
/* Disable all ENET mac interrupt and Clear all interrupt events*/
enet_hal_config_interrupt(devNumber, kEnetAllInterrupt, false);
enet_hal_clear_interrupt(devNumber, kEnetAllInterrupt);
/* Program this station's physical address*/
enet_hal_set_mac_address(devNumber, enetIfPtr->macCfgPtr->macAddr);
/* Clear group and individual hash register*/
enet_hal_set_group_hashtable(devNumber, 0, kEnetSpecialAddressInit);
enet_hal_set_individual_hashtable(devNumber, 0, kEnetSpecialAddressInit);
/* Configure mac controller*/
result = enet_mac_configure_controller(enetIfPtr);
if(result != kStatus_ENET_Success)
{
return result;
}
/* Clear mib zero counters*/
enet_hal_clear_mib(devNumber, true);
/* Initialize FIFO and accelerator*/
result = enet_mac_configure_fifo_accel(enetIfPtr);
if(result != kStatus_ENET_Success)
{
return result;
}
/* Initialize receive buffer descriptors*/
result = enet_mac_rxbd_init(enetIfPtr, rxbdCfg);
if(result != kStatus_ENET_Success)
{
return result;
}
/* Initialize transmit buffer descriptors*/
result = enet_mac_txbd_init(enetIfPtr, txbdCfg);
if(result != kStatus_ENET_Success)
{
return result;
}
/* Initialize rmii/mii interface*/
result = enet_mac_mii_init(enetIfPtr);
if (result != kStatus_ENET_Success)
{
return result;
}
return kStatus_ENET_Success;
}
/*******************************************************************************
* EOF
******************************************************************************/

View File

@ -844,14 +844,14 @@ err_t eth_arch_enetif_init(struct netif *netif)
}
void eth_arch_enable_interrupts(void) {
enet_hal_config_interrupt(BOARD_DEBUG_ENET_INSTANCE, (kEnetTxFrameInterrupt | kEnetRxFrameInterrupt), true);
interrupt_enable(enet_irq_ids[BOARD_DEBUG_ENET_INSTANCE][enetIntMap[kEnetRxfInt]]);
interrupt_enable(enet_irq_ids[BOARD_DEBUG_ENET_INSTANCE][enetIntMap[kEnetTxfInt]]);
enet_hal_config_interrupt(BOARD_DEBUG_ENET_INSTANCE, (kEnetTxFrameInterrupt | kEnetRxFrameInterrupt), true);
INT_SYS_EnableIRQ(enet_irq_ids[BOARD_DEBUG_ENET_INSTANCE][enetIntMap[kEnetRxfInt]]);
INT_SYS_EnableIRQ(enet_irq_ids[BOARD_DEBUG_ENET_INSTANCE][enetIntMap[kEnetTxfInt]]);
}
void eth_arch_disable_interrupts(void) {
interrupt_disable(enet_irq_ids[BOARD_DEBUG_ENET_INSTANCE][enetIntMap[kEnetRxfInt]]);
interrupt_disable(enet_irq_ids[BOARD_DEBUG_ENET_INSTANCE][enetIntMap[kEnetTxfInt]]);
INT_SYS_DisableIRQ(enet_irq_ids[BOARD_DEBUG_ENET_INSTANCE][enetIntMap[kEnetRxfInt]]);
INT_SYS_DisableIRQ(enet_irq_ids[BOARD_DEBUG_ENET_INSTANCE][enetIntMap[kEnetTxfInt]]);
}
void ENET_Transmit_IRQHandler(void)

View File

@ -14,6 +14,10 @@ DigitalIn in(D2);
DigitalOut out(PC_6);
DigitalIn in(PB_8);
#elif defined(TARGET_DISCO_F407VG)
DigitalOut out(PC_12);
DigitalIn in(PD_0);
#elif defined(TARGET_FF_ARDUINO)
DigitalOut out(D7);
DigitalIn in(D0);

View File

@ -10,10 +10,14 @@ DigitalInOut d2(dp2);
DigitalInOut d1(D2);
DigitalInOut d2(D7);
#elif defined(TARGET_NUCLEO_F103RB)
#elif defined(TARGET_NUCLEO_F103RB) || defined(TARGET_NUCLEO_F401RE) || defined(TARGET_NUCLEO_F411RE)
DigitalInOut d1(PC_6);
DigitalInOut d2(PB_8);
#elif defined(TARGET_DISCO_F407VG)
DigitalInOut d1(PC_12);
DigitalInOut d2(PD_0);
#elif defined(TARGET_FF_ARDUINO)
DigitalInOut d1(D0);
DigitalInOut d2(D7);

View File

@ -0,0 +1,52 @@
# 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-m4 -mthumb -mfpu=fpv4-sp-d16 -mfloat-abi=softfp
CC_FLAGS = $(CPU) -c -g -fno-common -fmessage-length=0 -Wall -fno-exceptions -ffunction-sections -fdata-sections -fomit-frame-pointer
CC_SYMBOLS = {% for s in symbols %}-D{{s}} {% endfor %}
LD_FLAGS = -mcpu=cortex-m4 -mthumb -Wl,--gc-sections --specs=nano.specs -u _printf_float -u _scanf_float
LD_SYS_LIBS = -lstdc++ -lsupc++ -lm -lc -lgcc -lnosys
ifeq ($(DEBUG), 1)
CC_FLAGS += -DDEBUG -O0
else
CC_FLAGS += -DNDEBUG -Os
endif
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 $< $@

View File

@ -29,6 +29,7 @@ class GccArm(Exporter):
'KL25Z',
'KL46Z',
'K64F',
'K22F',
'K20D50M',
'LPC4088',
'LPC4330_M4',

View File

@ -24,6 +24,7 @@ class KDS(Exporter):
TARGETS = [
'K64F',
'K22F',
]
def generate(self):

View File

@ -0,0 +1,306 @@
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<?fileVersion 4.0.0?><cproject storage_type_id="org.eclipse.cdt.core.XmlProjectDescriptionStorage">
<storageModule moduleId="org.eclipse.cdt.core.settings">
<cconfiguration id="ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug.637912026">
<storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug.637912026" moduleId="org.eclipse.cdt.core.settings" name="Debug">
<externalSettings/>
<extensions>
<extension id="org.eclipse.cdt.managedbuilder.core.ManagedBuildManager" point="org.eclipse.cdt.core.ScannerInfoProvider"/>
<extension id="org.eclipse.cdt.core.ELF" point="org.eclipse.cdt.core.BinaryParser"/>
<extension id="org.eclipse.cdt.core.GmakeErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
<extension id="org.eclipse.cdt.core.CWDLocator" point="org.eclipse.cdt.core.ErrorParser"/>
<extension id="org.eclipse.cdt.core.GCCErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
<extension id="org.eclipse.cdt.core.GASErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
<extension id="org.eclipse.cdt.core.GLDErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
</extensions>
</storageModule>
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
<configuration artifactName="${ProjName}" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.debug,org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe" cleanCommand="${cross_rm} -rf" description="" id="ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug.637912026" name="Debug" parent="ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug">
<folderInfo id="ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug.637912026." name="/" resourcePath="">
<toolChain id="ilg.gnuarmeclipse.managedbuild.cross.toolchain.elf.debug.1221610645" name="Cross ARM GCC" nonInternalBuilderId="ilg.gnuarmeclipse.managedbuild.cross.builder" superClass="ilg.gnuarmeclipse.managedbuild.cross.toolchain.elf.debug">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.level.1271983492" name="Optimization Level" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.level" value="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.level.none" valueType="enumerated"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.messagelength.1681866628" name="Message length (-fmessage-length=0)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.messagelength" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.signedchar.1550050553" name="'char' is signed (-fsigned-char)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.signedchar" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.functionsections.2126138943" name="Function sections (-ffunction-sections)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.functionsections" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.datasections.1492840277" name="Data sections (-fdata-sections)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.datasections" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.level.1058622512" name="Debug level" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.level" value="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.level.default" valueType="enumerated"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.format.1583945235" name="Debug format" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.format" value="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.format.gdb" valueType="enumerated"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.arm.target.family.1089911925" name="ARM family" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.arm.target.family" value="ilg.gnuarmeclipse.managedbuild.cross.option.arm.target.mcpu.cortex-m4" valueType="enumerated"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.arm.target.fpu.abi.77844367" name="Float ABI" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.arm.target.fpu.abi" value="ilg.gnuarmeclipse.managedbuild.cross.option.arm.target.fpu.abi.softfp" valueType="enumerated"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.arm.target.fpu.unit.353876552" name="FPU Type" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.arm.target.fpu.unit" value="ilg.gnuarmeclipse.managedbuild.cross.option.arm.target.fpu.unit.fpv4spd16" valueType="enumerated"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.toolchain.name.1308049896" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.toolchain.name" value="Custom" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.command.prefix.560926624" name="Prefix" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.command.prefix" value="arm-none-eabi-" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.command.c.660978974" name="C compiler" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.command.c" value="gcc" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.command.cpp.1169416449" name="C++ compiler" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.command.cpp" value="g++" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.command.objcopy.1545312724" name="Hex/Bin converter" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.command.objcopy" value="objcopy" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.command.objdump.2106299868" name="Listing generator" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.command.objdump" value="objdump" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.command.size.880150025" name="Size command" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.command.size" value="size" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.command.make.1449434602" name="Build command" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.command.make" value="make" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.command.rm.1638755745" name="Remove command" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.command.rm" value="rm" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.warnings.allwarn.1500383066" name="Enable all common warnings (-Wall)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.warnings.allwarn" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.createflash.choice.1422858690" name="Output file format (-O)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.createflash.choice" value="ilg.gnuarmeclipse.managedbuild.cross.option.createflash.choice.binary" valueType="enumerated"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.addtools.createflash.1453349108" name="Create flash image" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.addtools.createflash" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.nobuiltin.918192766" name="Disable builtin (-fno-builtin)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.nobuiltin" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.other.845411621" name="Other debugging flags" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.other" value="" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.prof.2076910080" name="Generate prof information (-p)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.prof" value="false" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.gprof.1002876099" name="Generate gprof information (-pg)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.gprof" value="false" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.addtools.printsize.371856963" name="Print size" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.addtools.printsize" value="true" valueType="boolean"/>
<targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.ELF" id="ilg.gnuarmeclipse.managedbuild.cross.targetPlatform.2090214221" isAbstract="false" osList="all" superClass="ilg.gnuarmeclipse.managedbuild.cross.targetPlatform"/>
<builder autoBuildTarget="all" buildPath="${workspace_loc:/{{name}}}/Debug" cleanBuildTarget="clean" command="${cross_make}" id="org.eclipse.cdt.build.core.internal.builder.2045347460" incrementalBuildTarget="all" managedBuildOn="true" name="CDT Internal Builder" superClass="org.eclipse.cdt.build.core.internal.builder"/>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.assembler.774448198" name="Cross ARM GNU Assembler" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.assembler">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.usepreprocessor.874144438" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.usepreprocessor" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.defs.1457752231" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.defs" valueType="definedSymbols">
{% for s in symbols %}
<listOptionValue builtIn="false" value="{{s}}"/>
{% endfor %}
</option>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.include.paths.1240528565" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.include.paths" valueType="includePath">
{% for path in include_paths %}
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/{{path}}}&quot;"/>
{% endfor %}
</option>
<inputType id="ilg.gnuarmeclipse.managedbuild.cross.tool.assembler.input.645447748" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.assembler.input"/>
</tool>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.1023327076" name="Cross ARM C Compiler" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.c.compiler.std.655157579" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.c.compiler.std" useByScannerDiscovery="true" value="ilg.gnuarmeclipse.managedbuild.cross.option.c.compiler.std.c99" valueType="enumerated"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.c.compiler.include.paths.1298012181" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.c.compiler.include.paths" useByScannerDiscovery="false" valueType="includePath">
{% for path in include_paths %}
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/{{path}}}&quot;"/>
{% endfor %}
</option>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.c.compiler.defs.26057600" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.c.compiler.defs" valueType="definedSymbols">
{% for s in symbols %}
<listOptionValue builtIn="false" value="{{s}}"/>
{% endfor %}
</option>
<inputType id="ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.input.247734571" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.input"/>
</tool>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.compiler.248936164" name="Cross ARM C++ Compiler" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.compiler">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.include.paths.1551083554" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.include.paths" valueType="includePath">
{% for path in include_paths %}
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/{{path}}}&quot;"/>
{% endfor %}
</option>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.defs.1601945676" name="Defined symbols (-D)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.defs" useByScannerDiscovery="false" valueType="definedSymbols">
{% for s in symbols %}
<listOptionValue builtIn="false" value="{{s}}"/>
{% endfor %}
</option>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.noexceptions.73762833" name="Do not use exceptions (-fno-exceptions)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.noexceptions" useByScannerDiscovery="true" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.nortti.1541205451" name="Do not use RTTI (-fno-rtti)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.nortti" useByScannerDiscovery="true" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.std.2072412260" name="Language standard" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.std" useByScannerDiscovery="true" value="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.std.default" valueType="enumerated"/>
<inputType id="ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.compiler.input.2029463372" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.compiler.input"/>
</tool>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.c.linker.1882430856" name="Cross ARM C Linker" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.c.linker">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.c.linker.gcsections.339583643" name="Remove unused sections (-Xlinker --gc-sections)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.c.linker.gcsections" value="true" valueType="boolean"/>
</tool>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.linker.1999194416" name="Cross ARM C++ Linker" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.linker">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.gcsections.344980185" name="Remove unused sections (-Xlinker --gc-sections)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.gcsections" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.paths.727573047" name="Library search path (-L)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.paths" valueType="libPaths">
{% if libraries %}
{% for path in include_paths %}
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/{{path}}}&quot;"/>
{% endfor %}
{% endif %}
</option>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.scriptfile.828171482" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.scriptfile" valueType="stringList">
<listOptionValue builtIn="false" value="${workspace_loc:/${ProjName}/{{linker_script}}}"/>
</option>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.libs.310068762" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.libs" valueType="libs">
{% for lib in libraries %}
<listOptionValue builtIn="false" value="{{lib}}"/>
{% endfor %}
</option>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.otherobjs.460736806" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.otherobjs" valueType="userObjs">
{% for path in object_files %}
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/{{path}}}&quot;"/>
{% endfor %}
</option>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.other.30848869" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.other" value="-nanolibc" valueType="string"/>
<inputType id="ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.linker.input.1081415325" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.linker.input">
<additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
<additionalInput kind="additionalinput" paths="$(LIBS)"/>
</inputType>
</tool>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.archiver.1216251638" name="Cross ARM GNU Archiver" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.archiver"/>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.createflash.1820796904" name="Cross ARM GNU Create Flash Image" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.createflash">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.createflash.choice.70927688" name="Output file format (-O)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.createflash.choice" value="ilg.gnuarmeclipse.managedbuild.cross.option.createflash.choice.binary" valueType="enumerated"/>
</tool>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.createlisting.721327636" name="Cross ARM GNU Create Listing" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.createlisting">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.source.625552450" name="Display source (--source|-S)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.source" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.allheaders.263758416" name="Display all headers (--all-headers|-x)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.allheaders" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.demangle.1024069673" name="Demangle names (--demangle|-C)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.demangle" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.linenumbers.1043375284" name="Display line numbers (--line-numbers|-l)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.linenumbers" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.wide.1671601569" name="Wide lines (--wide|-w)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.wide" value="true" valueType="boolean"/>
</tool>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.printsize.171400698" name="Cross ARM GNU Print Size" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.printsize">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.printsize.format.1102568395" name="Size format" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.printsize.format"/>
</tool>
</toolChain>
</folderInfo>
</configuration>
</storageModule>
<storageModule moduleId="org.eclipse.cdt.core.externalSettings"/>
</cconfiguration>
<cconfiguration id="ilg.gnuarmeclipse.managedbuild.cross.config.elf.release.1382253787">
<storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="ilg.gnuarmeclipse.managedbuild.cross.config.elf.release.1382253787" moduleId="org.eclipse.cdt.core.settings" name="Release">
<externalSettings/>
<extensions>
<extension id="org.eclipse.cdt.managedbuilder.core.ManagedBuildManager" point="org.eclipse.cdt.core.ScannerInfoProvider"/>
<extension id="org.eclipse.cdt.core.ELF" point="org.eclipse.cdt.core.BinaryParser"/>
<extension id="org.eclipse.cdt.core.GmakeErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
<extension id="org.eclipse.cdt.core.CWDLocator" point="org.eclipse.cdt.core.ErrorParser"/>
<extension id="org.eclipse.cdt.core.GCCErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
<extension id="org.eclipse.cdt.core.GASErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
<extension id="org.eclipse.cdt.core.GLDErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
</extensions>
</storageModule>
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
<configuration artifactName="${ProjName}" buildArtefactType="org.eclipse.cdt.build.core.buildArtefactType.exe" buildProperties="org.eclipse.cdt.build.core.buildType=org.eclipse.cdt.build.core.buildType.release,org.eclipse.cdt.build.core.buildArtefactType=org.eclipse.cdt.build.core.buildArtefactType.exe" cleanCommand="${cross_rm} -rf" description="" id="ilg.gnuarmeclipse.managedbuild.cross.config.elf.release.1382253787" name="Release" parent="ilg.gnuarmeclipse.managedbuild.cross.config.elf.release">
<folderInfo id="ilg.gnuarmeclipse.managedbuild.cross.config.elf.release.1382253787." name="/" resourcePath="">
<toolChain id="ilg.gnuarmeclipse.managedbuild.cross.toolchain.elf.release.765163102" name="Cross ARM GCC" superClass="ilg.gnuarmeclipse.managedbuild.cross.toolchain.elf.release">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.level.1271983492" name="Optimization Level" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.level" value="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.level.size" valueType="enumerated"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.messagelength.1681866628" name="Message length (-fmessage-length=0)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.messagelength" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.signedchar.1550050553" name="'char' is signed (-fsigned-char)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.signedchar" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.functionsections.2126138943" name="Function sections (-ffunction-sections)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.functionsections" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.datasections.1492840277" name="Data sections (-fdata-sections)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.datasections" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.level.1058622512" name="Debug level" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.level" value="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.level.default" valueType="enumerated"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.format.1583945235" name="Debug format" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.format" value="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.format.gdb" valueType="enumerated"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.arm.target.family.1089911925" name="ARM family" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.arm.target.family" value="ilg.gnuarmeclipse.managedbuild.cross.option.arm.target.mcpu.cortex-m4" valueType="enumerated"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.arm.target.fpu.abi.77844367" name="Float ABI" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.arm.target.fpu.abi" value="ilg.gnuarmeclipse.managedbuild.cross.option.arm.target.fpu.abi.softfp" valueType="enumerated"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.arm.target.fpu.unit.353876552" name="FPU Type" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.arm.target.fpu.unit" value="ilg.gnuarmeclipse.managedbuild.cross.option.arm.target.fpu.unit.fpv4spd16" valueType="enumerated"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.toolchain.name.1308049896" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.toolchain.name" value="Custom" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.command.prefix.560926624" name="Prefix" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.command.prefix" value="arm-none-eabi-" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.command.c.660978974" name="C compiler" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.command.c" value="gcc" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.command.cpp.1169416449" name="C++ compiler" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.command.cpp" value="g++" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.command.objcopy.1545312724" name="Hex/Bin converter" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.command.objcopy" value="objcopy" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.command.objdump.2106299868" name="Listing generator" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.command.objdump" value="objdump" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.command.size.880150025" name="Size command" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.command.size" value="size" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.command.make.1449434602" name="Build command" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.command.make" value="make" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.command.rm.1638755745" name="Remove command" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.command.rm" value="rm" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.warnings.allwarn.1500383066" name="Enable all common warnings (-Wall)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.warnings.allwarn" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.createflash.choice.1422858690" name="Output file format (-O)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.createflash.choice" value="ilg.gnuarmeclipse.managedbuild.cross.option.createflash.choice.binary" valueType="enumerated"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.addtools.createflash.1453349108" name="Create flash image" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.addtools.createflash" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.nobuiltin.918192766" name="Disable builtin (-fno-builtin)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.optimization.nobuiltin" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.other.845411621" name="Other debugging flags" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.other" value="" valueType="string"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.prof.2076910080" name="Generate prof information (-p)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.prof" value="false" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.gprof.1002876099" name="Generate gprof information (-pg)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.gprof" value="false" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.addtools.printsize.371856963" name="Print size" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.addtools.printsize" value="true" valueType="boolean"/>
<targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.ELF" id="ilg.gnuarmeclipse.managedbuild.cross.targetPlatform.2090214221" isAbstract="false" osList="all" superClass="ilg.gnuarmeclipse.managedbuild.cross.targetPlatform"/>
<builder autoBuildTarget="all" buildPath="${workspace_loc:/{{name}}}/Debug" cleanBuildTarget="clean" command="${cross_make}" id="org.eclipse.cdt.build.core.internal.builder.2045347460" incrementalBuildTarget="all" managedBuildOn="true" name="CDT Internal Builder" superClass="org.eclipse.cdt.build.core.internal.builder"/>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.assembler.774448198" name="Cross ARM GNU Assembler" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.assembler">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.usepreprocessor.874144438" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.usepreprocessor" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.defs.1457752231" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.defs" valueType="definedSymbols">
{% for s in symbols %}
<listOptionValue builtIn="false" value="{{s}}"/>
{% endfor %}
</option>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.include.paths.1240528565" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.include.paths" valueType="includePath">
{% for path in include_paths %}
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/{{path}}}&quot;"/>
{% endfor %}
</option>
<inputType id="ilg.gnuarmeclipse.managedbuild.cross.tool.assembler.input.645447748" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.assembler.input"/>
</tool>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.1023327076" name="Cross ARM C Compiler" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.c.compiler.std.655157579" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.c.compiler.std" useByScannerDiscovery="true" value="ilg.gnuarmeclipse.managedbuild.cross.option.c.compiler.std.c99" valueType="enumerated"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.c.compiler.include.paths.1298012181" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.c.compiler.include.paths" useByScannerDiscovery="false" valueType="includePath">
{% for path in include_paths %}
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/{{path}}}&quot;"/>
{% endfor %}
</option>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.c.compiler.defs.26057600" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.c.compiler.defs" valueType="definedSymbols">
{% for s in symbols %}
<listOptionValue builtIn="false" value="{{s}}"/>
{% endfor %}
</option>
<inputType id="ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.input.247734571" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.input"/>
</tool>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.compiler.248936164" name="Cross ARM C++ Compiler" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.compiler">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.include.paths.1551083554" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.include.paths" valueType="includePath">
{% for path in include_paths %}
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/{{path}}}&quot;"/>
{% endfor %}
</option>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.defs.1601945676" name="Defined symbols (-D)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.defs" useByScannerDiscovery="false" valueType="definedSymbols">
{% for s in symbols %}
<listOptionValue builtIn="false" value="{{s}}"/>
{% endfor %}
</option>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.noexceptions.73762833" name="Do not use exceptions (-fno-exceptions)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.noexceptions" useByScannerDiscovery="true" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.nortti.1541205451" name="Do not use RTTI (-fno-rtti)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.nortti" useByScannerDiscovery="true" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.std.2072412260" name="Language standard" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.std" useByScannerDiscovery="true" value="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.compiler.std.default" valueType="enumerated"/>
<inputType id="ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.compiler.input.2029463372" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.compiler.input"/>
</tool>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.c.linker.1882430856" name="Cross ARM C Linker" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.c.linker">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.c.linker.gcsections.339583643" name="Remove unused sections (-Xlinker --gc-sections)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.c.linker.gcsections" value="true" valueType="boolean"/>
</tool>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.linker.1999194416" name="Cross ARM C++ Linker" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.linker">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.gcsections.344980185" name="Remove unused sections (-Xlinker --gc-sections)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.gcsections" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.paths.727573047" name="Library search path (-L)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.paths" valueType="libPaths">
{% if libraries %}
{% for path in include_paths %}
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/{{path}}}&quot;"/>
{% endfor %}
{% endif %}
</option>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.scriptfile.828171482" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.scriptfile" valueType="stringList">
<listOptionValue builtIn="false" value="${workspace_loc:/${ProjName}/{{linker_script}}}"/>
</option>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.libs.310068762" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.libs" valueType="libs">
{% for lib in libraries %}
<listOptionValue builtIn="false" value="{{lib}}"/>
{% endfor %}
</option>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.otherobjs.460736806" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.otherobjs" valueType="userObjs">
{% for path in object_files %}
<listOptionValue builtIn="false" value="&quot;${workspace_loc:/${ProjName}/{{path}}}&quot;"/>
{% endfor %}
</option>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.other.30848869" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.cpp.linker.other" value="-nanolibc" valueType="string"/>
<inputType id="ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.linker.input.1081415325" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.linker.input">
<additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
<additionalInput kind="additionalinput" paths="$(LIBS)"/>
</inputType>
</tool>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.archiver.1216251638" name="Cross ARM GNU Archiver" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.archiver"/>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.createflash.1820796904" name="Cross ARM GNU Create Flash Image" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.createflash">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.createflash.choice.70927688" name="Output file format (-O)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.createflash.choice" value="ilg.gnuarmeclipse.managedbuild.cross.option.createflash.choice.binary" valueType="enumerated"/>
</tool>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.createlisting.721327636" name="Cross ARM GNU Create Listing" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.createlisting">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.source.625552450" name="Display source (--source|-S)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.source" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.allheaders.263758416" name="Display all headers (--all-headers|-x)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.allheaders" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.demangle.1024069673" name="Demangle names (--demangle|-C)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.demangle" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.linenumbers.1043375284" name="Display line numbers (--line-numbers|-l)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.linenumbers" value="true" valueType="boolean"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.wide.1671601569" name="Wide lines (--wide|-w)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.createlisting.wide" value="true" valueType="boolean"/>
</tool>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.printsize.171400698" name="Cross ARM GNU Print Size" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.printsize">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.printsize.format.1102568395" name="Size format" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.printsize.format"/>
</tool>
</toolChain>
</folderInfo>
</configuration>
</storageModule>
<storageModule moduleId="org.eclipse.cdt.core.externalSettings"/>
</cconfiguration>
</storageModule>
<storageModule moduleId="org.eclipse.cdt.core.LanguageSettingsProviders"/>
<storageModule moduleId="cdtBuildSystem" version="4.0.0">
<project id="{{name}}.ilg.gnuarmeclipse.managedbuild.cross.target.elf.829438011" name="Executable" projectType="ilg.gnuarmeclipse.managedbuild.cross.target.elf"/>
</storageModule>
<storageModule moduleId="scannerConfiguration">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
<scannerConfigBuildInfo instanceId="ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug.637912026;ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug.637912026.;ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.1023327076;ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.input.247734571">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
</scannerConfigBuildInfo>
<scannerConfigBuildInfo instanceId="ilg.gnuarmeclipse.managedbuild.cross.config.elf.release.1382253787;ilg.gnuarmeclipse.managedbuild.cross.config.elf.release.1382253787.;ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.compiler.307634730;ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.compiler.input.1070359138">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
</scannerConfigBuildInfo>
<scannerConfigBuildInfo instanceId="ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug.637912026;ilg.gnuarmeclipse.managedbuild.cross.config.elf.debug.637912026.;ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.compiler.248936164;ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.compiler.input.2029463372">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
</scannerConfigBuildInfo>
<scannerConfigBuildInfo instanceId="ilg.gnuarmeclipse.managedbuild.cross.config.elf.release.1382253787;ilg.gnuarmeclipse.managedbuild.cross.config.elf.release.1382253787.;ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.1300731881;ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.input.690792246">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
</scannerConfigBuildInfo>
</storageModule>
</cproject>

View File

@ -0,0 +1,27 @@
<?xml version="1.0" encoding="UTF-8"?>
<projectDescription>
<name>{{name}}</name>
<comment>This file was automagically generated by mbed.org. For more information, see http://mbed.org/handbook/Exporting-To-KDS</comment>
<projects>
</projects>
<buildSpec>
<buildCommand>
<name>org.eclipse.cdt.managedbuilder.core.genmakebuilder</name>
<triggers>clean,full,incremental,</triggers>
<arguments>
</arguments>
</buildCommand>
<buildCommand>
<name>org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder</name>
<triggers>full,incremental,</triggers>
<arguments>
</arguments>
</buildCommand>
</buildSpec>
<natures>
<nature>org.eclipse.cdt.core.cnature</nature>
<nature>org.eclipse.cdt.core.ccnature</nature>
<nature>org.eclipse.cdt.managedbuilder.core.managedBuildNature</nature>
<nature>org.eclipse.cdt.managedbuilder.core.ScannerConfigNature</nature>
</natures>
</projectDescription>

View File

@ -28,6 +28,7 @@ class Uvision4(Exporter):
'KL25Z',
'KL46Z',
'K64F',
'K22F',
'K20D50M',
'LPC1347',
'LPC1114',

View File

@ -0,0 +1,187 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<ProjectOpt xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="project_opt.xsd">
<SchemaVersion>1.0</SchemaVersion>
<Header>### uVision Project, (C) Keil Software</Header>
<Extensions>
<cExt>*.c</cExt>
<aExt>*.s*; *.src; *.a*</aExt>
<oExt>*.obj</oExt>
<lExt>*.lib</lExt>
<tExt>*.txt; *.h; *.inc</tExt>
<pExt>*.plm</pExt>
<CppX>*.cpp</CppX>
</Extensions>
<DaveTm>
<dwLowDateTime>0</dwLowDateTime>
<dwHighDateTime>0</dwHighDateTime>
</DaveTm>
<Target>
<TargetName>mbed FRDM-K22F</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<TargetOption>
<CLKADS>12000000</CLKADS>
<OPTTT>
<gFlags>0</gFlags>
<BeepAtEnd>1</BeepAtEnd>
<RunSim>1</RunSim>
<RunTarget>0</RunTarget>
</OPTTT>
<OPTHX>
<HexSelection>1</HexSelection>
<FlashByte>65535</FlashByte>
<HexRangeLowAddress>0</HexRangeLowAddress>
<HexRangeHighAddress>0</HexRangeHighAddress>
<HexOffset>0</HexOffset>
</OPTHX>
<OPTLEX>
<PageWidth>79</PageWidth>
<PageLength>66</PageLength>
<TabStop>8</TabStop>
<ListingPath>.\build\</ListingPath>
</OPTLEX>
<ListingPage>
<CreateCListing>1</CreateCListing>
<CreateAListing>1</CreateAListing>
<CreateLListing>1</CreateLListing>
<CreateIListing>0</CreateIListing>
<AsmCond>1</AsmCond>
<AsmSymb>1</AsmSymb>
<AsmXref>0</AsmXref>
<CCond>1</CCond>
<CCode>0</CCode>
<CListInc>0</CListInc>
<CSymb>0</CSymb>
<LinkerCodeListing>0</LinkerCodeListing>
</ListingPage>
<OPTXL>
<LMap>1</LMap>
<LComments>1</LComments>
<LGenerateSymbols>1</LGenerateSymbols>
<LLibSym>1</LLibSym>
<LLines>1</LLines>
<LLocSym>1</LLocSym>
<LPubSym>1</LPubSym>
<LXref>0</LXref>
<LExpSel>0</LExpSel>
</OPTXL>
<OPTFL>
<tvExp>1</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<IsCurrentTarget>1</IsCurrentTarget>
</OPTFL>
<CpuCode>0</CpuCode>
<DllOpt>
<SimDllName>SARMCM3.DLL</SimDllName>
<SimDllArguments>-MPU</SimDllArguments>
<SimDlgDllName>DCM.DLL</SimDlgDllName>
<SimDlgDllArguments>-pCM4</SimDlgDllArguments>
<TargetDllName>SARMCM3.DLL</TargetDllName>
<TargetDllArguments>-MPU</TargetDllArguments>
<TargetDlgDllName>TCM.DLL</TargetDlgDllName>
<TargetDlgDllArguments>-pCM4</TargetDlgDllArguments>
</DllOpt>
<DebugOpt>
<uSim>0</uSim>
<uTrg>1</uTrg>
<sLdApp>1</sLdApp>
<sGomain>1</sGomain>
<sRbreak>1</sRbreak>
<sRwatch>1</sRwatch>
<sRmem>1</sRmem>
<sRfunc>1</sRfunc>
<sRbox>1</sRbox>
<tLdApp>1</tLdApp>
<tGomain>1</tGomain>
<tRbreak>1</tRbreak>
<tRwatch>1</tRwatch>
<tRmem>1</tRmem>
<tRfunc>0</tRfunc>
<tRbox>1</tRbox>
<tRtrace>0</tRtrace>
<sRunDeb>0</sRunDeb>
<sLrtime>0</sLrtime>
<nTsel>13</nTsel>
<sDll></sDll>
<sDllPa></sDllPa>
<sDlgDll></sDlgDll>
<sDlgPa></sDlgPa>
<sIfile></sIfile>
<tDll></tDll>
<tDllPa></tDllPa>
<tDlgDll></tDlgDll>
<tDlgPa></tDlgPa>
<tIfile></tIfile>
<pMon>BIN\CMSIS_AGDI.dll</pMon>
</DebugOpt>
<TargetDriverDllRegistry>
<SetRegEntry>
<Number>0</Number>
<Key>DLGTARM</Key>
<Name>(1010=-1,-1,-1,-1,0)(1007=-1,-1,-1,-1,0)(1008=-1,-1,-1,-1,0)(1009=-1,-1,-1,-1,0)(1012=-1,-1,-1,-1,0)</Name>
</SetRegEntry>
<SetRegEntry>
<Number>0</Number>
<Key>CMSIS_AGDI</Key>
<Name>-X"MBED CMSIS-DAP" -U024002014C482E7AB1B6D3C2 -O2510 -S0 -C0 -P00 -N00("ARM CoreSight SW-DP") -D00(2BA01477) -L00(0) -FO15 -FD20000000 -FC4000 -FN1 -FF0MK_P1M0 -FS00 -FL0100000</Name>
</SetRegEntry>
</TargetDriverDllRegistry>
<Breakpoint/>
<DebugFlag>
<trace>0</trace>
<periodic>0</periodic>
<aLwin>0</aLwin>
<aCover>0</aCover>
<aSer1>0</aSer1>
<aSer2>0</aSer2>
<aPa>0</aPa>
<viewmode>0</viewmode>
<vrSel>0</vrSel>
<aSym>0</aSym>
<aTbox>0</aTbox>
<AscS1>0</AscS1>
<AscS2>0</AscS2>
<AscS3>0</AscS3>
<aSer3>0</aSer3>
<eProf>0</eProf>
<aLa>0</aLa>
<aPa1>0</aPa1>
<AscS4>0</AscS4>
<aSer4>0</aSer4>
<StkLoc>0</StkLoc>
<TrcWin>0</TrcWin>
<newCpu>0</newCpu>
<uProt>0</uProt>
</DebugFlag>
<LintExecutable></LintExecutable>
<LintConfigFile></LintConfigFile>
</TargetOption>
</Target>
<Group>
<GroupName>src</GroupName>
<tvExp>1</tvExp>
<tvExpOptDlg>0</tvExpOptDlg>
<cbSel>0</cbSel>
<File>
<GroupNumber>1</GroupNumber>
<FileNumber>1</FileNumber>
<FileType>8</FileType>
<tvExp>0</tvExp>
<Focus>0</Focus>
<ColumnNumber>0</ColumnNumber>
<tvExpOptDlg>0</tvExpOptDlg>
<TopLine>1</TopLine>
<CurrentLine>2</CurrentLine>
<bDave2>0</bDave2>
<PathWithFileName>main.cpp</PathWithFileName>
<FilenameWithoutPath>main.cpp</FilenameWithoutPath>
</File>
</Group>
</ProjectOpt>

View File

@ -0,0 +1,425 @@
<?xml version="1.0" encoding="UTF-8" standalone="no" ?>
<Project xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="project_proj.xsd">
<SchemaVersion>1.1</SchemaVersion>
<Header>###This file was automagically generated by mbed.org. For more information, see http://mbed.org/handbook/Exporting-To-Uvision </Header>
<Targets>
<Target>
<TargetName>mbed FRDM-K22F</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<TargetOption>
<TargetCommonOption>
<Device>MK22FN512xxx12</Device>
<Vendor>Freescale Semiconductor</Vendor>
<Cpu>IROM(0x00000000,0x80000) IRAM(0x20000000,0x10000) IRAM2(0x1FFF0000,0x10000) CPUTYPE("Cortex-M4") FPU2 CLOCK(120000000) ELITTLE</Cpu>
<FlashUtilSpec></FlashUtilSpec>
<StartupFile></StartupFile>
<FlashDriverDll>UL2CM3(-S0 -C0 -P0 -FD20000000 -FC1000 -FN1 -FF0MK_P512 -FS00 -FL080000 -FP0($$Device:MK22FN512xxx12$Flash\MK_P512.FLM))</FlashDriverDll>
<DeviceId>0</DeviceId>
<RegisterFile>$$Device:MK22FN512xxx12$Device\Include\MK22F51212.h</RegisterFile>
<MemoryEnv></MemoryEnv>
<Cmp></Cmp>
<Asm></Asm>
<Linker></Linker>
<OHString></OHString>
<InfinionOptionDll></InfinionOptionDll>
<SLE66CMisc></SLE66CMisc>
<SLE66AMisc></SLE66AMisc>
<SLE66LinkerMisc></SLE66LinkerMisc>
<SFDFile>$$Device:MK22FN512xxx12$SVD\MK22F51212.svd</SFDFile>
<bCustSvd>0</bCustSvd>
<UseEnv>0</UseEnv>
<BinPath></BinPath>
<IncludePath></IncludePath>
<LibPath></LibPath>
<RegisterFilePath></RegisterFilePath>
<DBRegisterFilePath></DBRegisterFilePath>
<TargetStatus>
<Error>0</Error>
<ExitCodeStop>0</ExitCodeStop>
<ButtonStop>0</ButtonStop>
<NotGenerated>0</NotGenerated>
<InvalidFlash>1</InvalidFlash>
</TargetStatus>
<OutputDirectory>.\build\</OutputDirectory>
<OutputName>{{name}}</OutputName>
<CreateExecutable>1</CreateExecutable>
<CreateLib>0</CreateLib>
<CreateHexFile>0</CreateHexFile>
<DebugInformation>1</DebugInformation>
<BrowseInformation>1</BrowseInformation>
<ListingPath>.\build\</ListingPath>
<HexFormatSelection>1</HexFormatSelection>
<Merge32K>0</Merge32K>
<CreateBatchFile>0</CreateBatchFile>
<BeforeCompile>
<RunUserProg1>0</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
<nStopU1X>0</nStopU1X>
<nStopU2X>0</nStopU2X>
</BeforeCompile>
<BeforeMake>
<RunUserProg1>0</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name></UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
</BeforeMake>
<AfterMake>
<RunUserProg1>1</RunUserProg1>
<RunUserProg2>0</RunUserProg2>
<UserProg1Name>fromelf --bin -o build\{{name}}_K22F.bin build\{{name}}.axf</UserProg1Name>
<UserProg2Name></UserProg2Name>
<UserProg1Dos16Mode>0</UserProg1Dos16Mode>
<UserProg2Dos16Mode>0</UserProg2Dos16Mode>
</AfterMake>
<SelectedForBatchBuild>0</SelectedForBatchBuild>
<SVCSIdString></SVCSIdString>
</TargetCommonOption>
<CommonProperty>
<UseCPPCompiler>0</UseCPPCompiler>
<RVCTCodeConst>0</RVCTCodeConst>
<RVCTZI>0</RVCTZI>
<RVCTOtherData>0</RVCTOtherData>
<ModuleSelection>0</ModuleSelection>
<IncludeInBuild>1</IncludeInBuild>
<AlwaysBuild>0</AlwaysBuild>
<GenerateAssemblyFile>0</GenerateAssemblyFile>
<AssembleAssemblyFile>0</AssembleAssemblyFile>
<PublicsOnly>0</PublicsOnly>
<StopOnExitCode>3</StopOnExitCode>
<CustomArgument></CustomArgument>
<IncludeLibraryModules></IncludeLibraryModules>
</CommonProperty>
<DllOption>
<SimDllName>SARMCM3.DLL</SimDllName>
<SimDllArguments>-MPU</SimDllArguments>
<SimDlgDll>DCM.DLL</SimDlgDll>
<SimDlgDllArguments>-pCM4</SimDlgDllArguments>
<TargetDllName>SARMCM3.DLL</TargetDllName>
<TargetDllArguments>-MPU</TargetDllArguments>
<TargetDlgDll>TCM.DLL</TargetDlgDll>
<TargetDlgDllArguments>-pCM4</TargetDlgDllArguments>
</DllOption>
<DebugOption>
<OPTHX>
<HexSelection>1</HexSelection>
<HexRangeLowAddress>0</HexRangeLowAddress>
<HexRangeHighAddress>0</HexRangeHighAddress>
<HexOffset>0</HexOffset>
<Oh166RecLen>16</Oh166RecLen>
</OPTHX>
<Simulator>
<UseSimulator>0</UseSimulator>
<LoadApplicationAtStartup>1</LoadApplicationAtStartup>
<RunToMain>1</RunToMain>
<RestoreBreakpoints>1</RestoreBreakpoints>
<RestoreWatchpoints>1</RestoreWatchpoints>
<RestoreMemoryDisplay>1</RestoreMemoryDisplay>
<RestoreFunctions>1</RestoreFunctions>
<RestoreToolbox>1</RestoreToolbox>
<LimitSpeedToRealTime>0</LimitSpeedToRealTime>
</Simulator>
<Target>
<UseTarget>1</UseTarget>
<LoadApplicationAtStartup>1</LoadApplicationAtStartup>
<RunToMain>1</RunToMain>
<RestoreBreakpoints>1</RestoreBreakpoints>
<RestoreWatchpoints>1</RestoreWatchpoints>
<RestoreMemoryDisplay>1</RestoreMemoryDisplay>
<RestoreFunctions>0</RestoreFunctions>
<RestoreToolbox>1</RestoreToolbox>
</Target>
<RunDebugAfterBuild>0</RunDebugAfterBuild>
<TargetSelection>13</TargetSelection>
<SimDlls>
<CpuDll></CpuDll>
<CpuDllArguments></CpuDllArguments>
<PeripheralDll></PeripheralDll>
<PeripheralDllArguments></PeripheralDllArguments>
<InitializationFile></InitializationFile>
</SimDlls>
<TargetDlls>
<CpuDll></CpuDll>
<CpuDllArguments></CpuDllArguments>
<PeripheralDll></PeripheralDll>
<PeripheralDllArguments></PeripheralDllArguments>
<InitializationFile></InitializationFile>
<Driver>BIN\CMSIS_AGDI.dll</Driver>
</TargetDlls>
</DebugOption>
<Utilities>
<Flash1>
<UseTargetDll>1</UseTargetDll>
<UseExternalTool>0</UseExternalTool>
<RunIndependent>0</RunIndependent>
<UpdateFlashBeforeDebugging>1</UpdateFlashBeforeDebugging>
<Capability>1</Capability>
<DriverSelection>4104</DriverSelection>
</Flash1>
<bUseTDR>0</bUseTDR>
<Flash2>BIN\CMSIS_AGDI.dll</Flash2>
<Flash3>"" ()</Flash3>
<Flash4></Flash4>
</Utilities>
<TargetArmAds>
<ArmAdsMisc>
<GenerateListings>0</GenerateListings>
<asHll>1</asHll>
<asAsm>1</asAsm>
<asMacX>1</asMacX>
<asSyms>1</asSyms>
<asFals>1</asFals>
<asDbgD>1</asDbgD>
<asForm>1</asForm>
<ldLst>0</ldLst>
<ldmm>1</ldmm>
<ldXref>1</ldXref>
<BigEnd>0</BigEnd>
<AdsALst>1</AdsALst>
<AdsACrf>1</AdsACrf>
<AdsANop>0</AdsANop>
<AdsANot>0</AdsANot>
<AdsLLst>1</AdsLLst>
<AdsLmap>1</AdsLmap>
<AdsLcgr>1</AdsLcgr>
<AdsLsym>1</AdsLsym>
<AdsLszi>1</AdsLszi>
<AdsLtoi>1</AdsLtoi>
<AdsLsun>1</AdsLsun>
<AdsLven>1</AdsLven>
<AdsLsxf>1</AdsLsxf>
<RvctClst>0</RvctClst>
<GenPPlst>0</GenPPlst>
<AdsCpuType>"Cortex-M4"</AdsCpuType>
<RvctDeviceName></RvctDeviceName>
<mOS>0</mOS>
<uocRom>0</uocRom>
<uocRam>0</uocRam>
<hadIROM>1</hadIROM>
<hadIRAM>1</hadIRAM>
<hadXRAM>0</hadXRAM>
<uocXRam>0</uocXRam>
<RvdsVP>0</RvdsVP>
<hadIRAM2>1</hadIRAM2>
<hadIROM2>0</hadIROM2>
<StupSel>8</StupSel>
<useUlib>0</useUlib>
<EndSel>0</EndSel>
<uLtcg>0</uLtcg>
<RoSelD>3</RoSelD>
<RwSelD>3</RwSelD>
<CodeSel>0</CodeSel>
<OptFeed>0</OptFeed>
<NoZi1>0</NoZi1>
<NoZi2>0</NoZi2>
<NoZi3>0</NoZi3>
<NoZi4>0</NoZi4>
<NoZi5>0</NoZi5>
<Ro1Chk>0</Ro1Chk>
<Ro2Chk>0</Ro2Chk>
<Ro3Chk>0</Ro3Chk>
<Ir1Chk>1</Ir1Chk>
<Ir2Chk>0</Ir2Chk>
<Ra1Chk>0</Ra1Chk>
<Ra2Chk>0</Ra2Chk>
<Ra3Chk>0</Ra3Chk>
<Im1Chk>1</Im1Chk>
<Im2Chk>0</Im2Chk>
<OnChipMemories>
<Ocm1>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm1>
<Ocm2>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm2>
<Ocm3>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm3>
<Ocm4>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm4>
<Ocm5>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm5>
<Ocm6>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</Ocm6>
<IRAM>
<Type>0</Type>
<StartAddress>0x1fff0000</StartAddress>
<Size>0x10000</Size>
</IRAM>
<IROM>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x100000</Size>
</IROM>
<XRAM>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</XRAM>
<OCR_RVCT1>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT1>
<OCR_RVCT2>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT2>
<OCR_RVCT3>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT3>
<OCR_RVCT4>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x80000</Size>
</OCR_RVCT4>
<OCR_RVCT5>
<Type>1</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT5>
<OCR_RVCT6>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT6>
<OCR_RVCT7>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT7>
<OCR_RVCT8>
<Type>0</Type>
<StartAddress>0x0</StartAddress>
<Size>0x0</Size>
</OCR_RVCT8>
<OCR_RVCT9>
<Type>0</Type>
<StartAddress>0x20000000</StartAddress>
<Size>0x10000</Size>
</OCR_RVCT9>
<OCR_RVCT10>
<Type>0</Type>
<StartAddress>0x1fff0000</StartAddress>
<Size>0x10000</Size>
</OCR_RVCT10>
</OnChipMemories>
<RvctStartVector></RvctStartVector>
</ArmAdsMisc>
<Cads>
<interw>1</interw>
<Optim>1</Optim>
<oTime>0</oTime>
<SplitLS>0</SplitLS>
<OneElfS>0</OneElfS>
<Strict>0</Strict>
<EnumInt>0</EnumInt>
<PlainCh>0</PlainCh>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<wLevel>0</wLevel>
<uThumb>0</uThumb>
<uSurpInc>0</uSurpInc>
<VariousControls>
<MiscControls>{% for flag in flags %}{{flag}} {% endfor %} --pch --pch_dir=build</MiscControls>
<Define>{% for s in symbols %} {{s}}, {% endfor %}</Define>
<Undefine></Undefine>
<IncludePath> {% for path in include_paths %} {{path}}; {% endfor %} </IncludePath>
</VariousControls>
</Cads>
<Aads>
<interw>1</interw>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<thumb>0</thumb>
<SplitLS>0</SplitLS>
<SwStkChk>0</SwStkChk>
<NoWarn>0</NoWarn>
<uSurpInc>0</uSurpInc>
<VariousControls>
<MiscControls></MiscControls>
<Define></Define>
<Undefine></Undefine>
<IncludePath></IncludePath>
</VariousControls>
</Aads>
<LDads>
<umfTarg>0</umfTarg>
<Ropi>0</Ropi>
<Rwpi>0</Rwpi>
<noStLib>0</noStLib>
<RepFail>1</RepFail>
<useFile>0</useFile>
<TextAddressRange>0x00000000</TextAddressRange>
<DataAddressRange>0x20000000</DataAddressRange>
<ScatterFile>{{scatter_file}}</ScatterFile>
<IncludeLibs></IncludeLibs>
<IncludeLibsPath></IncludeLibsPath>
<Misc>
{% for file in object_files %}
{{file}}
{% endfor %}
</Misc>
<LinkerInputFile></LinkerInputFile>
<DisabledWarnings></DisabledWarnings>
</LDads>
</TargetArmAds>
</TargetOption>
<Groups>
{% for group,files in source_files %}
<Group>
<GroupName>{{group}}</GroupName>
<Files>
{% for file in files %}
<File>
<FileName>{{file.name}}</FileName>
<FileType>{{file.type}}</FileType>
<FilePath>{{file.path}}</FilePath>
{%if file.type == "1" %}
<FileOption>
<FileArmAds>
<Cads>
<VariousControls>
<MiscControls>--c99</MiscControls>
</VariousControls>
</Cads>
</FileArmAds>
</FileOption>
{% endif %}
</File>
{% endfor %}
</Files>
</Group>
{% endfor %}
</Groups>
</Target>
</Targets>
</Project>