diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K22F/TOOLCHAIN_GCC_ARM/K22FN512xxx12.ld b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K22F/TOOLCHAIN_GCC_ARM/K22FN512xxx12.ld new file mode 100644 index 0000000000..b7b3fe61c2 --- /dev/null +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K22F/TOOLCHAIN_GCC_ARM/K22FN512xxx12.ld @@ -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") +} + diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K22F/TOOLCHAIN_GCC_ARM/startup_MK22F12.S b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K22F/TOOLCHAIN_GCC_ARM/startup_MK22F12.S new file mode 100644 index 0000000000..2b56751648 --- /dev/null +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K22F/TOOLCHAIN_GCC_ARM/startup_MK22F12.S @@ -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 diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_KPSDK_MCUS/TARGET_KPSDK_CODE/drivers/interrupt/src/fsl_interrupt_manager.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_KPSDK_MCUS/TARGET_KPSDK_CODE/drivers/interrupt/src/fsl_interrupt_manager.c deleted file mode 100644 index b3002b9c4c..0000000000 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_KPSDK_MCUS/TARGET_KPSDK_CODE/drivers/interrupt/src/fsl_interrupt_manager.c +++ /dev/null @@ -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 -#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 - ******************************************************************************/ - diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_KPSDK_MCUS/TARGET_KPSDK_CODE/utilities/src/sw_timer.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_KPSDK_MCUS/TARGET_KPSDK_CODE/utilities/src/sw_timer.c deleted file mode 100644 index 9b6b69cf6c..0000000000 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_KPSDK_MCUS/TARGET_KPSDK_CODE/utilities/src/sw_timer.c +++ /dev/null @@ -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 - ******************************************************************************/ - diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F401RE/PinNames.h b/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F401RE/PinNames.h index 67def4f980..6c82cf53b7 100644 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F401RE/PinNames.h +++ b/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F401RE/PinNames.h @@ -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 diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F401RE/gpio_irq_api.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F401RE/gpio_irq_api.c index 47f0883692..2db6b33642 100644 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F401RE/gpio_irq_api.c +++ b/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F401RE/gpio_irq_api.c @@ -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)); diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F401RE/pinmap.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F401RE/pinmap.c index 01afd00dab..4036119f21 100644 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F401RE/pinmap.c +++ b/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F401RE/pinmap.c @@ -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 diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F411RE/PinNames.h b/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F411RE/PinNames.h index 67def4f980..6c82cf53b7 100644 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F411RE/PinNames.h +++ b/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F411RE/PinNames.h @@ -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 diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F411RE/gpio_irq_api.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F411RE/gpio_irq_api.c index 42ba48870b..54b74e4317 100644 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F411RE/gpio_irq_api.c +++ b/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F411RE/gpio_irq_api.c @@ -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)); diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F411RE/pinmap.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F411RE/pinmap.c index 524733cdad..a0ea2f2ef7 100644 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F411RE/pinmap.c +++ b/libraries/mbed/targets/hal/TARGET_STM/TARGET_NUCLEO_F411RE/pinmap.c @@ -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 diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F407VG/TARGET_DISCO_F407VG/PinNames.h b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F407VG/TARGET_DISCO_F407VG/PinNames.h index 1b45662c81..be4907df97 100644 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F407VG/TARGET_DISCO_F407VG/PinNames.h +++ b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F407VG/TARGET_DISCO_F407VG/PinNames.h @@ -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 diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F407VG/gpio_irq_api.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F407VG/gpio_irq_api.c index db8fdeed6c..bd09b785b2 100644 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F407VG/gpio_irq_api.c +++ b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F407VG/gpio_irq_api.c @@ -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)); diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F407VG/pinmap.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F407VG/pinmap.c index db80f3fece..c2e873cc71 100644 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F407VG/pinmap.c +++ b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F407VG/pinmap.c @@ -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 diff --git a/libraries/net/eth/lwip-eth/arch/TARGET_Freescale/fsl_enet_driver.c b/libraries/net/eth/lwip-eth/arch/TARGET_Freescale/fsl_enet_driver.c new file mode 100644 index 0000000000..10137cd912 --- /dev/null +++ b/libraries/net/eth/lwip-eth/arch/TARGET_Freescale/fsl_enet_driver.c @@ -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 + +#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 + ******************************************************************************/ + diff --git a/libraries/net/eth/lwip-eth/arch/TARGET_Freescale/k64f_emac.c b/libraries/net/eth/lwip-eth/arch/TARGET_Freescale/k64f_emac.c index 4e3dc54994..b81e25f3b9 100644 --- a/libraries/net/eth/lwip-eth/arch/TARGET_Freescale/k64f_emac.c +++ b/libraries/net/eth/lwip-eth/arch/TARGET_Freescale/k64f_emac.c @@ -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) diff --git a/libraries/tests/mbed/digitalin_digitalout/main.cpp b/libraries/tests/mbed/digitalin_digitalout/main.cpp index a698dbeca9..8b9ec6db4b 100644 --- a/libraries/tests/mbed/digitalin_digitalout/main.cpp +++ b/libraries/tests/mbed/digitalin_digitalout/main.cpp @@ -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); diff --git a/libraries/tests/mbed/digitalinout/main.cpp b/libraries/tests/mbed/digitalinout/main.cpp index 6744c00229..718539e42a 100644 --- a/libraries/tests/mbed/digitalinout/main.cpp +++ b/libraries/tests/mbed/digitalinout/main.cpp @@ -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); diff --git a/workspace_tools/export/gcc_arm_k22f.tmpl b/workspace_tools/export/gcc_arm_k22f.tmpl new file mode 100644 index 0000000000..b3c69bf883 --- /dev/null +++ b/workspace_tools/export/gcc_arm_k22f.tmpl @@ -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 $< $@ diff --git a/workspace_tools/export/gccarm.py b/workspace_tools/export/gccarm.py index f002b680d1..b44405929e 100644 --- a/workspace_tools/export/gccarm.py +++ b/workspace_tools/export/gccarm.py @@ -29,6 +29,7 @@ class GccArm(Exporter): 'KL25Z', 'KL46Z', 'K64F', + 'K22F', 'K20D50M', 'LPC4088', 'LPC4330_M4', diff --git a/workspace_tools/export/kds.py b/workspace_tools/export/kds.py index f7db7195eb..b22ec11fd9 100644 --- a/workspace_tools/export/kds.py +++ b/workspace_tools/export/kds.py @@ -24,6 +24,7 @@ class KDS(Exporter): TARGETS = [ 'K64F', + 'K22F', ] def generate(self): diff --git a/workspace_tools/export/kds_k22f_cproject.tmpl b/workspace_tools/export/kds_k22f_cproject.tmpl new file mode 100644 index 0000000000..5aa8af1bce --- /dev/null +++ b/workspace_tools/export/kds_k22f_cproject.tmpl @@ -0,0 +1,306 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/workspace_tools/export/kds_k22f_project.tmpl b/workspace_tools/export/kds_k22f_project.tmpl new file mode 100644 index 0000000000..1ab5ab3485 --- /dev/null +++ b/workspace_tools/export/kds_k22f_project.tmpl @@ -0,0 +1,27 @@ + + + {{name}} + This file was automagically generated by mbed.org. For more information, see http://mbed.org/handbook/Exporting-To-KDS + + + + + org.eclipse.cdt.managedbuilder.core.genmakebuilder + clean,full,incremental, + + + + + org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder + full,incremental, + + + + + + org.eclipse.cdt.core.cnature + org.eclipse.cdt.core.ccnature + org.eclipse.cdt.managedbuilder.core.managedBuildNature + org.eclipse.cdt.managedbuilder.core.ScannerConfigNature + + diff --git a/workspace_tools/export/uvision4.py b/workspace_tools/export/uvision4.py index 12a01e9acd..bcd427c6d1 100644 --- a/workspace_tools/export/uvision4.py +++ b/workspace_tools/export/uvision4.py @@ -28,6 +28,7 @@ class Uvision4(Exporter): 'KL25Z', 'KL46Z', 'K64F', + 'K22F', 'K20D50M', 'LPC1347', 'LPC1114', diff --git a/workspace_tools/export/uvision4_k22f.uvopt.tmpl b/workspace_tools/export/uvision4_k22f.uvopt.tmpl new file mode 100644 index 0000000000..531b5525bd --- /dev/null +++ b/workspace_tools/export/uvision4_k22f.uvopt.tmpl @@ -0,0 +1,187 @@ + + + + 1.0 + +
### uVision Project, (C) Keil Software
+ + + *.c + *.s*; *.src; *.a* + *.obj + *.lib + *.txt; *.h; *.inc + *.plm + *.cpp + + + + 0 + 0 + + + + mbed FRDM-K22F + 0x4 + ARM-ADS + + 12000000 + + 0 + 1 + 1 + 0 + + + 1 + 65535 + 0 + 0 + 0 + + + 79 + 66 + 8 + .\build\ + + + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 0 + 0 + 0 + 0 + + + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + + + 1 + 0 + 1 + + 0 + + SARMCM3.DLL + -MPU + DCM.DLL + -pCM4 + SARMCM3.DLL + -MPU + TCM.DLL + -pCM4 + + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 0 + 0 + 0 + 13 + + + + + + + + + + + BIN\CMSIS_AGDI.dll + + + + 0 + DLGTARM + (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) + + + 0 + CMSIS_AGDI + -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 + + + + + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + + + src + 1 + 0 + 0 + + 1 + 1 + 8 + 0 + 0 + 0 + 0 + 1 + 2 + 0 + main.cpp + main.cpp + + + +
diff --git a/workspace_tools/export/uvision4_k22f.uvproj.tmpl b/workspace_tools/export/uvision4_k22f.uvproj.tmpl new file mode 100644 index 0000000000..f814662e37 --- /dev/null +++ b/workspace_tools/export/uvision4_k22f.uvproj.tmpl @@ -0,0 +1,425 @@ + + + + 1.1 + +
###This file was automagically generated by mbed.org. For more information, see http://mbed.org/handbook/Exporting-To-Uvision
+ + + + mbed FRDM-K22F + 0x4 + ARM-ADS + + + MK22FN512xxx12 + Freescale Semiconductor + IROM(0x00000000,0x80000) IRAM(0x20000000,0x10000) IRAM2(0x1FFF0000,0x10000) CPUTYPE("Cortex-M4") FPU2 CLOCK(120000000) ELITTLE + + + UL2CM3(-S0 -C0 -P0 -FD20000000 -FC1000 -FN1 -FF0MK_P512 -FS00 -FL080000 -FP0($$Device:MK22FN512xxx12$Flash\MK_P512.FLM)) + 0 + $$Device:MK22FN512xxx12$Device\Include\MK22F51212.h + + + + + + + + + + $$Device:MK22FN512xxx12$SVD\MK22F51212.svd + 0 + 0 + + + + + + + 0 + 0 + 0 + 0 + 1 + + .\build\ + {{name}} + 1 + 0 + 0 + 1 + 1 + .\build\ + 1 + 0 + 0 + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 0 + 0 + + + 0 + 0 + + + 1 + 0 + fromelf --bin -o build\{{name}}_K22F.bin build\{{name}}.axf + + 0 + 0 + + 0 + + + + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 3 + + + + + SARMCM3.DLL + -MPU + DCM.DLL + -pCM4 + SARMCM3.DLL + -MPU + TCM.DLL + -pCM4 + + + + 1 + 0 + 0 + 0 + 16 + + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + + + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + + 0 + 13 + + + + + + + + + + + + + + BIN\CMSIS_AGDI.dll + + + + + 1 + 0 + 0 + 1 + 1 + 4104 + + 0 + BIN\CMSIS_AGDI.dll + "" () + + + + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + "Cortex-M4" + + 0 + 0 + 0 + 1 + 1 + 0 + 0 + 0 + 1 + 0 + 8 + 0 + 0 + 0 + 3 + 3 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 1 + 0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x1fff0000 + 0x10000 + + + 1 + 0x0 + 0x100000 + + + 0 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x80000 + + + 1 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x20000000 + 0x10000 + + + 0 + 0x1fff0000 + 0x10000 + + + + + + 1 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + {% for flag in flags %}{{flag}} {% endfor %} --pch --pch_dir=build + {% for s in symbols %} {{s}}, {% endfor %} + + {% for path in include_paths %} {{path}}; {% endfor %} + + + + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + 0 + 1 + 0 + 0x00000000 + 0x20000000 + {{scatter_file}} + + + + {% for file in object_files %} + {{file}} + {% endfor %} + + + + + + + + {% for group,files in source_files %} + + {{group}} + + {% for file in files %} + + {{file.name}} + {{file.type}} + {{file.path}} + {%if file.type == "1" %} + + + + + --c99 + + + + + {% endif %} + + {% endfor %} + + + {% endfor %} + + + + +