From 5bd25ac0460cb4206ce1d2a8f1796259271aee7c Mon Sep 17 00:00:00 2001 From: Michael Conners Date: Tue, 24 Sep 2013 10:36:04 -0400 Subject: [PATCH 01/33] Added K20D5M support --- .../TARGET_Freescale/TARGET_K20D5M/MK20D5.h | 5836 +++++++++++++++++ .../TARGET_K20D5M/TOOLCHAIN_GCC_ARM/MK20D5.ld | 163 + .../TOOLCHAIN_GCC_ARM/startup_MK20D5.s | 214 + .../TARGET_Freescale/TARGET_K20D5M/cmsis.h | 13 + .../TARGET_K20D5M/cmsis_nvic.c | 30 + .../TARGET_K20D5M/cmsis_nvic.h | 26 + .../TARGET_K20D5M/system_MK20D5.c | 278 + .../TARGET_K20D5M/system_MK20D5.h | 87 + .../TARGET_K20D5M/PeripheralNames.h | 89 + .../TARGET_Freescale/TARGET_K20D5M/PinNames.h | 248 + .../TARGET_K20D5M/PortNames.h | 34 + .../TARGET_K20D5M/analogin_api.c | 94 + .../TARGET_Freescale/TARGET_K20D5M/device.h | 58 + .../TARGET_Freescale/TARGET_K20D5M/gpio_api.c | 54 + .../TARGET_K20D5M/gpio_irq_api.c | 145 + .../TARGET_K20D5M/gpio_object.h | 49 + .../TARGET_Freescale/TARGET_K20D5M/i2c_api.c | 423 ++ .../TARGET_Freescale/TARGET_K20D5M/objects.h | 75 + .../TARGET_Freescale/TARGET_K20D5M/pinmap.c | 39 + .../TARGET_Freescale/TARGET_K20D5M/port_api.c | 68 + .../TARGET_K20D5M/pwmout_api.c | 142 + .../TARGET_Freescale/TARGET_K20D5M/rtc_api.c | 91 + .../TARGET_K20D5M/serial_api.c | 303 + .../TARGET_Freescale/TARGET_K20D5M/spi_api.c | 200 + .../TARGET_K20D5M/us_ticker.c | 146 + workspace_tools/targets.py | 13 + 26 files changed, 8918 insertions(+) create mode 100644 libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/MK20D5.h create mode 100644 libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/MK20D5.ld create mode 100644 libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/startup_MK20D5.s create mode 100644 libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis.h create mode 100644 libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis_nvic.c create mode 100644 libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis_nvic.h create mode 100644 libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/system_MK20D5.c create mode 100644 libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/system_MK20D5.h create mode 100644 libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PeripheralNames.h create mode 100644 libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PinNames.h create mode 100644 libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PortNames.h create mode 100644 libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/analogin_api.c create mode 100644 libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/device.h create mode 100644 libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_api.c create mode 100644 libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_irq_api.c create mode 100644 libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_object.h create mode 100644 libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/i2c_api.c create mode 100644 libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/objects.h create mode 100644 libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pinmap.c create mode 100644 libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/port_api.c create mode 100644 libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pwmout_api.c create mode 100644 libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/rtc_api.c create mode 100644 libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/serial_api.c create mode 100644 libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/spi_api.c create mode 100644 libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/us_ticker.c diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/MK20D5.h b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/MK20D5.h new file mode 100644 index 0000000000..bd430e10bd --- /dev/null +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/MK20D5.h @@ -0,0 +1,5836 @@ +/* +** ################################################################### +** Compilers: ARM Compiler +** Freescale C/C++ for Embedded ARM +** GNU C Compiler +** IAR ANSI C/C++ Compiler for ARM +** +** Reference manuals: K20P64M50SF0RM Rev. 1, Oct 2011 +** K20P32M50SF0RM Rev. 1, Oct 2011 +** K20P48M50SF0RM Rev. 1, Oct 2011 +** +** Version: rev. 2.0, 2012-03-19 +** +** Abstract: +** CMSIS Peripheral Access Layer for MK20D5 +** +** Copyright: 1997 - 2012 Freescale Semiconductor, Inc. All Rights Reserved. +** +** http: www.freescale.com +** mail: support@freescale.com +** +** Revisions: +** - rev. 1.0 (2011-12-15) +** Initial version +** - rev. 2.0 (2012-03-19) +** PDB Peripheral register structure updated. +** DMA Registers and bits for unsupported DMA channels removed. +** +** ################################################################### +*/ + +/** + * @file MK20D5.h + * @version 2.0 + * @date 2012-03-19 + * @brief CMSIS Peripheral Access Layer for MK20D5 + * + * CMSIS Peripheral Access Layer for MK20D5 + */ + +#if !defined(MK20D5_H_) +#define MK20D5_H_ /**< Symbol preventing repeated inclusion */ + +/** Memory map major version (memory maps with equal major version number are + * compatible) */ +#define MCU_MEM_MAP_VERSION 0x0200u +/** Memory map minor version */ +#define MCU_MEM_MAP_VERSION_MINOR 0x0000u + +/** + * @brief Macro to access a single bit of a peripheral register (bit band region + * 0x40000000 to 0x400FFFFF) using the bit-band alias region access. + * @param Reg Register to access. + * @param Bit Bit number to access. + * @return Value of the targeted bit in the bit band region. + */ +#define BITBAND_REG(Reg,Bit) (*((uint32_t volatile*)(0x42000000u + (32u*((uint32_t)&(Reg) - (uint32_t)0x40000000u)) + (4u*((uint32_t)(Bit)))))) + +/* ---------------------------------------------------------------------------- + -- Interrupt vector numbers + ---------------------------------------------------------------------------- */ + +/** + * @addtogroup Interrupt_vector_numbers Interrupt vector numbers + * @{ + */ + +/** Interrupt Number Definitions */ +typedef enum IRQn { + /* Core interrupts */ + NonMaskableInt_IRQn = -14, /**< Non Maskable Interrupt */ + MemoryManagement_IRQn = -12, /**< Cortex-M4 Memory Management Interrupt */ + BusFault_IRQn = -11, /**< Cortex-M4 Bus Fault Interrupt */ + UsageFault_IRQn = -10, /**< Cortex-M4 Usage Fault Interrupt */ + SVCall_IRQn = -5, /**< Cortex-M4 SV Call Interrupt */ + DebugMonitor_IRQn = -4, /**< Cortex-M4 Debug Monitor Interrupt */ + PendSV_IRQn = -2, /**< Cortex-M4 Pend SV Interrupt */ + SysTick_IRQn = -1, /**< Cortex-M4 System Tick Interrupt */ + + /* Device specific interrupts */ + DMA0_IRQn = 0, /**< DMA channel 0 transfer complete interrupt */ + DMA1_IRQn = 1, /**< DMA channel 1 transfer complete interrupt */ + DMA2_IRQn = 2, /**< DMA channel 2 transfer complete interrupt */ + DMA3_IRQn = 3, /**< DMA channel 3 transfer complete interrupt */ + DMA_Error_IRQn = 4, /**< DMA error interrupt */ + Reserved21_IRQn = 5, /**< Reserved interrupt 21 */ + FTFL_IRQn = 6, /**< FTFL interrupt */ + Read_Collision_IRQn = 7, /**< Read collision interrupt */ + LVD_LVW_IRQn = 8, /**< Low Voltage Detect, Low Voltage Warning */ + LLW_IRQn = 9, /**< Low Leakage Wakeup */ + Watchdog_IRQn = 10, /**< WDOG interrupt */ + I2C0_IRQn = 11, /**< I2C0 interrupt */ + SPI0_IRQn = 12, /**< SPI0 interrupt */ + I2S0_Tx_IRQn = 13, /**< I2S0 transmit interrupt */ + I2S0_Rx_IRQn = 14, /**< I2S0 receive interrupt */ + UART0_LON_IRQn = 15, /**< UART0 LON interrupt */ + UART0_RX_TX_IRQn = 16, /**< UART0 receive/transmit interrupt */ + UART0_ERR_IRQn = 17, /**< UART0 error interrupt */ + UART1_RX_TX_IRQn = 18, /**< UART1 receive/transmit interrupt */ + UART1_ERR_IRQn = 19, /**< UART1 error interrupt */ + UART2_RX_TX_IRQn = 20, /**< UART2 receive/transmit interrupt */ + UART2_ERR_IRQn = 21, /**< UART2 error interrupt */ + ADC0_IRQn = 22, /**< ADC0 interrupt */ + CMP0_IRQn = 23, /**< CMP0 interrupt */ + CMP1_IRQn = 24, /**< CMP1 interrupt */ + FTM0_IRQn = 25, /**< FTM0 fault, overflow and channels interrupt */ + FTM1_IRQn = 26, /**< FTM1 fault, overflow and channels interrupt */ + CMT_IRQn = 27, /**< CMT interrupt */ + RTC_IRQn = 28, /**< RTC interrupt */ + RTC_Seconds_IRQn = 29, /**< RTC seconds interrupt */ + PIT0_IRQn = 30, /**< PIT timer channel 0 interrupt */ + PIT1_IRQn = 31, /**< PIT timer channel 1 interrupt */ + PIT2_IRQn = 32, /**< PIT timer channel 2 interrupt */ + PIT3_IRQn = 33, /**< PIT timer channel 3 interrupt */ + PDB0_IRQn = 34, /**< PDB0 interrupt */ + USB0_IRQn = 35, /**< USB0 interrupt */ + USBDCD_IRQn = 36, /**< USBDCD interrupt */ + TSI0_IRQn = 37, /**< TSI0 interrupt */ + MCG_IRQn = 38, /**< MCG interrupt */ + LPTimer_IRQn = 39, /**< LPTimer interrupt */ + PORTA_IRQn = 40, /**< Port A interrupt */ + PORTB_IRQn = 41, /**< Port B interrupt */ + PORTC_IRQn = 42, /**< Port C interrupt */ + PORTD_IRQn = 43, /**< Port D interrupt */ + PORTE_IRQn = 44, /**< Port E interrupt */ + SWI_IRQn = 45 /**< Software interrupt */ +} IRQn_Type; + +/** + * @} + */ /* end of group Interrupt_vector_numbers */ + + +/* ---------------------------------------------------------------------------- + -- Cortex M4 Core Configuration + ---------------------------------------------------------------------------- */ + +/** + * @addtogroup Cortex_Core_Configuration Cortex M4 Core Configuration + * @{ + */ + +#define __MPU_PRESENT 0 /**< Defines if an MPU is present or not */ +#define __NVIC_PRIO_BITS 4 /**< Number of priority bits implemented in the NVIC */ +#define __Vendor_SysTickConfig 0 /**< Vendor specific implementation of SysTickConfig is defined */ + +#include "core_cm4.h" /* Core Peripheral Access Layer */ +#include "system_MK20D5.h" /* Device specific configuration file */ + +/** + * @} + */ /* end of group Cortex_Core_Configuration */ + + +/* ---------------------------------------------------------------------------- + -- Device Peripheral Access Layer + ---------------------------------------------------------------------------- */ + +/** + * @addtogroup Peripheral_access_layer Device Peripheral Access Layer + * @{ + */ + + +/* +** Start of section using anonymous unions +*/ + +#if defined(__ARMCC_VERSION) + #pragma push + #pragma anon_unions +#elif defined(__CWCC__) + #pragma push + #pragma cpp_extensions on +#elif defined(__GNUC__) + /* anonymous unions are enabled by default */ +#elif defined(__IAR_SYSTEMS_ICC__) + #pragma language=extended +#else + #error Not supported compiler type +#endif + +/* ---------------------------------------------------------------------------- + -- ADC Peripheral Access Layer + ---------------------------------------------------------------------------- */ + +/** + * @addtogroup ADC_Peripheral_Access_Layer ADC Peripheral Access Layer + * @{ + */ + +/** ADC - Register Layout Typedef */ +typedef struct { + __IO uint32_t SC1[2]; /**< ADC status and control registers 1, array offset: 0x0, array step: 0x4 */ + __IO uint32_t CFG1; /**< ADC configuration register 1, offset: 0x8 */ + __IO uint32_t CFG2; /**< Configuration register 2, offset: 0xC */ + __I uint32_t R[2]; /**< ADC data result register, array offset: 0x10, array step: 0x4 */ + __IO uint32_t CV1; /**< Compare value registers, offset: 0x18 */ + __IO uint32_t CV2; /**< Compare value registers, offset: 0x1C */ + __IO uint32_t SC2; /**< Status and control register 2, offset: 0x20 */ + __IO uint32_t SC3; /**< Status and control register 3, offset: 0x24 */ + __IO uint32_t OFS; /**< ADC offset correction register, offset: 0x28 */ + __IO uint32_t PG; /**< ADC plus-side gain register, offset: 0x2C */ + __IO uint32_t MG; /**< ADC minus-side gain register, offset: 0x30 */ + __IO uint32_t CLPD; /**< ADC plus-side general calibration value register, offset: 0x34 */ + __IO uint32_t CLPS; /**< ADC plus-side general calibration value register, offset: 0x38 */ + __IO uint32_t CLP4; /**< ADC plus-side general calibration value register, offset: 0x3C */ + __IO uint32_t CLP3; /**< ADC plus-side general calibration value register, offset: 0x40 */ + __IO uint32_t CLP2; /**< ADC plus-side general calibration value register, offset: 0x44 */ + __IO uint32_t CLP1; /**< ADC plus-side general calibration value register, offset: 0x48 */ + __IO uint32_t CLP0; /**< ADC plus-side general calibration value register, offset: 0x4C */ + uint8_t RESERVED_0[4]; + __IO uint32_t CLMD; /**< ADC minus-side general calibration value register, offset: 0x54 */ + __IO uint32_t CLMS; /**< ADC minus-side general calibration value register, offset: 0x58 */ + __IO uint32_t CLM4; /**< ADC minus-side general calibration value register, offset: 0x5C */ + __IO uint32_t CLM3; /**< ADC minus-side general calibration value register, offset: 0x60 */ + __IO uint32_t CLM2; /**< ADC minus-side general calibration value register, offset: 0x64 */ + __IO uint32_t CLM1; /**< ADC minus-side general calibration value register, offset: 0x68 */ + __IO uint32_t CLM0; /**< ADC minus-side general calibration value register, offset: 0x6C */ +} ADC_Type; + +/* ---------------------------------------------------------------------------- + -- ADC Register Masks + ---------------------------------------------------------------------------- */ + +/** + * @addtogroup ADC_Register_Masks ADC Register Masks + * @{ + */ + +/* SC1 Bit Fields */ +#define ADC_SC1_ADCH_MASK 0x1Fu +#define ADC_SC1_ADCH_SHIFT 0 +#define ADC_SC1_ADCH(x) (((uint32_t)(((uint32_t)(x))< 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_K20D5M/TOOLCHAIN_GCC_ARM/startup_MK20D5.s b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/startup_MK20D5.s new file mode 100644 index 0000000000..554be8349d --- /dev/null +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/startup_MK20D5.s @@ -0,0 +1,214 @@ +/* File: startup_ARMCM4.S + * Purpose: startup file for Cortex-M4 devices. Should use with + * GCC for ARM Embedded Processors + * Version: V1.3 + * Date: 08 Feb 2012 + * + * Copyright (c) 2012, 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 + + .section .stack + .align 3 +#ifdef __STACK_SIZE + .equ Stack_Size, __STACK_SIZE +#else + .equ Stack_Size, 0x400 +#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, 0xC00 +#endif + .globl __HeapBase + .globl __HeapLimit +__HeapBase: + .if Heap_Size + .space Heap_Size + .endif + .size __HeapBase, . - __HeapBase +__HeapLimit: + .size __HeapLimit, . - __HeapLimit + + .section .isr_vector + .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 WDT_IRQHandler /* 0: Watchdog Timer */ + .long RTC_IRQHandler /* 1: Real Time Clock */ + .long TIM0_IRQHandler /* 2: Timer0 / Timer1 */ + .long TIM2_IRQHandler /* 3: Timer2 / Timer3 */ + .long MCIA_IRQHandler /* 4: MCIa */ + .long MCIB_IRQHandler /* 5: MCIb */ + .long UART0_IRQHandler /* 6: UART0 - DUT FPGA */ + .long UART1_IRQHandler /* 7: UART1 - DUT FPGA */ + .long UART2_IRQHandler /* 8: UART2 - DUT FPGA */ + .long UART4_IRQHandler /* 9: UART4 - not connected */ + .long AACI_IRQHandler /* 10: AACI / AC97 */ + .long CLCD_IRQHandler /* 11: CLCD Combined Interrupt */ + .long ENET_IRQHandler /* 12: Ethernet */ + .long USBDC_IRQHandler /* 13: USB Device */ + .long USBHC_IRQHandler /* 14: USB Host Controller */ + .long CHLCD_IRQHandler /* 15: Character LCD */ + .long FLEXRAY_IRQHandler /* 16: Flexray */ + .long CAN_IRQHandler /* 17: CAN */ + .long LIN_IRQHandler /* 18: LIN */ + .long I2C_IRQHandler /* 19: I2C ADC/DAC */ + .long 0 /* 20: Reserved */ + .long 0 /* 21: Reserved */ + .long 0 /* 22: Reserved */ + .long 0 /* 23: Reserved */ + .long 0 /* 24: Reserved */ + .long 0 /* 25: Reserved */ + .long 0 /* 26: Reserved */ + .long 0 /* 27: Reserved */ + .long CPU_CLCD_IRQHandler /* 28: Reserved - CPU FPGA CLCD */ + .long 0 /* 29: Reserved - CPU FPGA */ + .long UART3_IRQHandler /* 30: UART3 - CPU FPGA */ + .long SPI_IRQHandler /* 31: SPI Touchscreen - CPU FPGA */ + + .size __isr_vector, . - __isr_vector + + .text + .thumb + .thumb_func + .align 2 + .globl Reset_Handler + .type Reset_Handler, %function +Reset_Handler: +/* Loop to copy data from read only memory to RAM. The ranges + * of copy from/to are specified by following symbols evaluated in + * linker script. + * __etext: End of code section, i.e., begin of data sections to copy from. + * __data_start__/__data_end__: RAM address range that data should be + * copied to. Both must be aligned to 4 bytes boundary. */ + + ldr r1, =__etext + ldr r2, =__data_start__ + ldr r3, =__data_end__ + + +/* Here are two copies of loop implemenations. First one favors code size + * and the second one favors performance. Default uses the first one. + * Change to "#if 0" to use the second one */ +.flash_to_ram_loop: + cmp r2, r3 + ittt lt + ldrlt r0, [r1], #4 + strlt r0, [r2], #4 + blt .flash_to_ram_loop + +.flash_to_ram_loop_end: + + +#ifndef __NO_SYSTEM_INIT + ldr r0, =SystemInit + blx r0 +#endif + + ldr r0, =_start + bx r0 + .pool + .size Reset_Handler, . - Reset_Handler + +/* Macro to define default handlers. Default handler + * will be weak symbol and just dead loops. They can be + * overwritten by other handlers */ + .macro def_irq_handler handler_name + .align 1 + .thumb_func + .weak \handler_name + .type \handler_name, %function +\handler_name : + b . + .size \handler_name, . - \handler_name + .endm + + def_irq_handler NMI_Handler + def_irq_handler HardFault_Handler + def_irq_handler MemManage_Handler + def_irq_handler BusFault_Handler + def_irq_handler UsageFault_Handler + def_irq_handler SVC_Handler + def_irq_handler DebugMon_Handler + def_irq_handler PendSV_Handler + def_irq_handler SysTick_Handler + def_irq_handler Default_Handler + + def_irq_handler WDT_IRQHandler + def_irq_handler RTC_IRQHandler + def_irq_handler TIM0_IRQHandler + def_irq_handler TIM2_IRQHandler + def_irq_handler MCIA_IRQHandler + def_irq_handler MCIB_IRQHandler + def_irq_handler UART0_IRQHandler + def_irq_handler UART1_IRQHandler + def_irq_handler UART2_IRQHandler + def_irq_handler UART3_IRQHandler + def_irq_handler UART4_IRQHandler + def_irq_handler AACI_IRQHandler + def_irq_handler CLCD_IRQHandler + def_irq_handler ENET_IRQHandler + def_irq_handler USBDC_IRQHandler + def_irq_handler USBHC_IRQHandler + def_irq_handler CHLCD_IRQHandler + def_irq_handler FLEXRAY_IRQHandler + def_irq_handler CAN_IRQHandler + def_irq_handler LIN_IRQHandler + def_irq_handler I2C_IRQHandler + def_irq_handler CPU_CLCD_IRQHandler + def_irq_handler SPI_IRQHandler + + .end diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis.h b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis.h new file mode 100644 index 0000000000..bebfa6d698 --- /dev/null +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis.h @@ -0,0 +1,13 @@ +/* mbed Microcontroller Library - CMSIS + * Copyright (C) 2009-2011 ARM Limited. All rights reserved. + * + * A generic CMSIS include header, pulling in LPC11U24 specifics + */ + +#ifndef MBED_CMSIS_H +#define MBED_CMSIS_H + +#include "MK20D5.h" +#include "cmsis_nvic.h" + +#endif diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis_nvic.c b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis_nvic.c new file mode 100644 index 0000000000..a15284bf92 --- /dev/null +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis_nvic.c @@ -0,0 +1,30 @@ +/* mbed Microcontroller Library - cmsis_nvic for LPC11U24 + * Copyright (c) 2011 ARM Limited. All rights reserved. + * + * CMSIS-style functionality to support dynamic vectors + */ +#include "cmsis_nvic.h" + +#define NVIC_RAM_VECTOR_ADDRESS (0x1FFFF000) // Vectors positioned at start of RAM +#define NVIC_FLASH_VECTOR_ADDRESS (0x0) // Initial vector position in flash + +void NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) { + uint32_t *vectors = (uint32_t*)SCB->VTOR; + uint32_t i; + + // Copy and switch to dynamic vectors if the first time called + if (SCB->VTOR == NVIC_FLASH_VECTOR_ADDRESS) { + uint32_t *old_vectors = vectors; + vectors = (uint32_t*)NVIC_RAM_VECTOR_ADDRESS; + for (i=0; iVTOR = (uint32_t)NVIC_RAM_VECTOR_ADDRESS; + } + vectors[IRQn + 16] = vector; +} + +uint32_t NVIC_GetVector(IRQn_Type IRQn) { + uint32_t *vectors = (uint32_t*)SCB->VTOR; + return vectors[IRQn + 16]; +} diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis_nvic.h b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis_nvic.h new file mode 100644 index 0000000000..6acdca9efd --- /dev/null +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis_nvic.h @@ -0,0 +1,26 @@ +/* mbed Microcontroller Library - cmsis_nvic + * Copyright (c) 2009-2011 ARM Limited. All rights reserved. + * + * CMSIS-style functionality to support dynamic vectors + */ + +#ifndef MBED_CMSIS_NVIC_H +#define MBED_CMSIS_NVIC_H + +#define NVIC_NUM_VECTORS (16 + 32) // CORE + MCU Peripherals +#define NVIC_USER_IRQ_OFFSET 16 + +#include "cmsis.h" + +#ifdef __cplusplus +extern "C" { +#endif + +void NVIC_SetVector(IRQn_Type IRQn, uint32_t vector); +uint32_t NVIC_GetVector(IRQn_Type IRQn); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/system_MK20D5.c b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/system_MK20D5.c new file mode 100644 index 0000000000..b78b71a707 --- /dev/null +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/system_MK20D5.c @@ -0,0 +1,278 @@ +/* +** ################################################################### +** Compilers: ARM Compiler +** Freescale C/C++ for Embedded ARM +** GNU C Compiler +** IAR ANSI C/C++ Compiler for ARM +** +** Reference manuals: K20P64M50SF0RM Rev. 1, Oct 2011 +** K20P32M50SF0RM Rev. 1, Oct 2011 +** K20P48M50SF0RM Rev. 1, Oct 2011 +** +** Version: rev. 1.0, 2011-12-15 +** +** Abstract: +** Provides a system configuration function and a global variable that +** contains the system frequency. It configures the device and initializes +** the oscillator (PLL) that is part of the microcontroller device. +** +** Copyright: 2011 Freescale Semiconductor, Inc. All Rights Reserved. +** +** http: www.freescale.com +** mail: support@freescale.com +** +** Revisions: +** - rev. 1.0 (2011-12-15) +** Initial version +** +** ################################################################### +*/ + +/** + * @file MK20D5 + * @version 1.0 + * @date 2011-12-15 + * @brief Device specific configuration file for MK20D5 (implementation file) + * + * Provides a system configuration function and a global variable that contains + * the system frequency. It configures the device and initializes the oscillator + * (PLL) that is part of the microcontroller device. + */ + +#include +#include "MK20D5.h" + +#define DISABLE_WDOG 1 + +#define CLOCK_SETUP 0 +/* Predefined clock setups + 0 ... Multipurpose Clock Generator (MCG) in FLL Engaged Internal (FEI) mode + Reference clock source for MCG module is the slow internal clock source 32.768kHz + Core clock = 41.94MHz, BusClock = 41.94MHz + 1 ... Multipurpose Clock Generator (MCG) in PLL Engaged External (PEE) mode + Reference clock source for MCG module is an external crystal 8MHz + Core clock = 48MHz, BusClock = 48MHz + 2 ... Multipurpose Clock Generator (MCG) in Bypassed Low Power External (BLPE) mode + Core clock/Bus clock derived directly from an external crystal 8MHz with no multiplication + Core clock = 8MHz, BusClock = 8MHz +*/ + +/*---------------------------------------------------------------------------- + Define clock source values + *----------------------------------------------------------------------------*/ +#if (CLOCK_SETUP == 0) + #define CPU_XTAL_CLK_HZ 8000000u /* Value of the external crystal or oscillator clock frequency in Hz */ + #define CPU_XTAL32k_CLK_HZ 32768u /* Value of the external 32k crystal or oscillator clock frequency in Hz */ + #define CPU_INT_SLOW_CLK_HZ 32768u /* Value of the slow internal oscillator clock frequency in Hz */ + #define CPU_INT_FAST_CLK_HZ 4000000u /* Value of the fast internal oscillator clock frequency in Hz */ + #define DEFAULT_SYSTEM_CLOCK 41943040u /* Default System clock value */ +#elif (CLOCK_SETUP == 1) + #define CPU_XTAL_CLK_HZ 8000000u /* Value of the external crystal or oscillator clock frequency in Hz */ + #define CPU_XTAL32k_CLK_HZ 32768u /* Value of the external 32k crystal or oscillator clock frequency in Hz */ + #define CPU_INT_SLOW_CLK_HZ 32768u /* Value of the slow internal oscillator clock frequency in Hz */ + #define CPU_INT_FAST_CLK_HZ 4000000u /* Value of the fast internal oscillator clock frequency in Hz */ + #define DEFAULT_SYSTEM_CLOCK 48000000u /* Default System clock value */ +#elif (CLOCK_SETUP == 2) + #define CPU_XTAL_CLK_HZ 8000000u /* Value of the external crystal or oscillator clock frequency in Hz */ + #define CPU_XTAL32k_CLK_HZ 32768u /* Value of the external 32k crystal or oscillator clock frequency in Hz */ + #define CPU_INT_SLOW_CLK_HZ 32768u /* Value of the slow internal oscillator clock frequency in Hz */ + #define CPU_INT_FAST_CLK_HZ 4000000u /* Value of the fast internal oscillator clock frequency in Hz */ + #define DEFAULT_SYSTEM_CLOCK 8000000u /* Default System clock value */ +#endif /* (CLOCK_SETUP == 2) */ + + +/* ---------------------------------------------------------------------------- + -- Core clock + ---------------------------------------------------------------------------- */ + +uint32_t SystemCoreClock = DEFAULT_SYSTEM_CLOCK; + +/* ---------------------------------------------------------------------------- + -- SystemInit() + ---------------------------------------------------------------------------- */ + +void SystemInit (void) { +#if (DISABLE_WDOG) + /* Disable the WDOG module */ + /* WDOG_UNLOCK: WDOGUNLOCK=0xC520 */ + WDOG->UNLOCK = (uint16_t)0xC520u; /* Key 1 */ + /* WDOG_UNLOCK : WDOGUNLOCK=0xD928 */ + WDOG->UNLOCK = (uint16_t)0xD928u; /* Key 2 */ + /* WDOG_STCTRLH: ??=0,DISTESTWDOG=0,BYTESEL=0,TESTSEL=0,TESTWDOG=0,??=0,STNDBYEN=1,WAITEN=1,STOPEN=1,DBGEN=0,ALLOWUPDATE=1,WINEN=0,IRQRSTEN=0,CLKSRC=1,WDOGEN=0 */ + WDOG->STCTRLH = (uint16_t)0x01D2u; +#endif /* (DISABLE_WDOG) */ +#if (CLOCK_SETUP == 0) + /* SIM->CLKDIV1: OUTDIV1=0,OUTDIV2=0,OUTDIV3=1,OUTDIV4=1,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0 */ + SIM->CLKDIV1 = (uint32_t)0x00110000u; /* Update system prescalers */ + /* Switch to FEI Mode */ + /* MCG->C1: CLKS=0,FRDIV=0,IREFS=1,IRCLKEN=1,IREFSTEN=0 */ + MCG->C1 = (uint8_t)0x06u; + /* MCG->C2: ??=0,??=0,RANGE0=0,HGO=0,EREFS=0,LP=0,IRCS=0 */ + MCG->C2 = (uint8_t)0x00u; + /* MCG_C4: DMX32=0,DRST_DRS=1 */ + MCG->C4 = (uint8_t)((MCG->C4 & (uint8_t)~(uint8_t)0xC0u) | (uint8_t)0x20u); + /* MCG->C5: ??=0,PLLCLKEN=0,PLLSTEN=0,PRDIV0=0 */ + MCG->C5 = (uint8_t)0x00u; + /* MCG->C6: LOLIE=0,PLLS=0,CME=0,VDIV0=0 */ + MCG->C6 = (uint8_t)0x00u; + while((MCG->S & MCG_S_IREFST_MASK) == 0u) { /* Check that the source of the FLL reference clock is the internal reference clock. */ + } + while((MCG->S & 0x0Cu) != 0x00u) { /* Wait until output of the FLL is selected */ + } +#elif (CLOCK_SETUP == 1) + /* SIM->CLKDIV1: OUTDIV1=0,OUTDIV2=0,OUTDIV3=1,OUTDIV4=1,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0 */ + SIM->CLKDIV1 = (uint32_t)0x00110000u; /* Update system prescalers */ + /* Switch to FBE Mode */ + /* OSC0->CR: ERCLKEN=0,??=0,EREFSTEN=0,??=0,SC2P=0,SC4P=0,SC8P=0,SC16P=0 */ + OSC0->CR = (uint8_t)0x00u; + /* MCG->C7: OSCSEL=0 */ + MCG->C7 = (uint8_t)0x00u; + /* MCG->C2: ??=0,??=0,RANGE0=2,HGO=0,EREFS=1,LP=0,IRCS=0 */ + MCG->C2 = (uint8_t)0x24u; + /* MCG->C1: CLKS=2,FRDIV=3,IREFS=0,IRCLKEN=1,IREFSTEN=0 */ + MCG->C1 = (uint8_t)0x9Au; + /* MCG->C4: DMX32=0,DRST_DRS=0 */ + MCG->C4 &= (uint8_t)~(uint8_t)0xE0u; + /* MCG->C5: ??=0,PLLCLKEN=0,PLLSTEN=0,PRDIV0=3 */ + MCG->C5 = (uint8_t)0x03u; + /* MCG->C6: LOLIE=0,PLLS=0,CME=0,VDIV0=0 */ + MCG->C6 = (uint8_t)0x00u; + while((MCG->S & MCG_S_OSCINIT0_MASK) == 0u) { /* Check that the oscillator is running */ + } +#if 0 /* ARM: THIS CHECK IS REMOVED DUE TO BUG WITH SLOW IRC IN REV. 1.0 */ + while((MCG->S & MCG_S_IREFST_MASK) != 0u) { /* Check that the source of the FLL reference clock is the external reference clock. */ + } +#endif + while((MCG->S & 0x0Cu) != 0x08u) { /* Wait until external reference clock is selected as MCG output */ + } + /* Switch to PBE Mode */ + /* MCG_C5: ??=0,PLLCLKEN=0,PLLSTEN=0,PRDIV0=3 */ + MCG->C5 = (uint8_t)0x03u; + /* MCG->C6: LOLIE=0,PLLS=1,CME=0,VDIV0=0 */ + MCG->C6 = (uint8_t)0x40u; + while((MCG->S & MCG_S_PLLST_MASK) == 0u) { /* Wait until the source of the PLLS clock has switched to the PLL */ + } + while((MCG->S & MCG_S_LOCK0_MASK) == 0u) { /* Wait until locked */ + } + /* Switch to PEE Mode */ + /* MCG->C1: CLKS=0,FRDIV=3,IREFS=0,IRCLKEN=1,IREFSTEN=0 */ + MCG->C1 = (uint8_t)0x1Au; + while((MCG->S & 0x0Cu) != 0x0Cu) { /* Wait until output of the PLL is selected */ + } + while((MCG->S & MCG_S_LOCK0_MASK) == 0u) { /* Wait until locked */ + } +#elif (CLOCK_SETUP == 2) + /* SIM_CLKDIV1: OUTDIV1=0,OUTDIV2=0,OUTDIV3=1,OUTDIV4=1,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0 */ + SIM->CLKDIV1 = (uint32_t)0x00110000u; /* Update system prescalers */ + /* Switch to FBE Mode */ + /* OSC0->CR: ERCLKEN=0,??=0,EREFSTEN=0,??=0,SC2P=0,SC4P=0,SC8P=0,SC16P=0 */ + OSC0->CR = (uint8_t)0x00u; + /* MCG->C7: OSCSEL=0 */ + MCG->C7 = (uint8_t)0x00u; + /* MCG->C2: ??=0,??=0,RANGE0=2,HGO=0,EREFS=1,LP=0,IRCS=0 */ + MCG->C2 = (uint8_t)0x24u; + /* MCG->C1: CLKS=2,FRDIV=3,IREFS=0,IRCLKEN=1,IREFSTEN=0 */ + MCG->C1 = (uint8_t)0x9Au; + /* MCG->C4: DMX32=0,DRST_DRS=0 */ + MCG->C4 &= (uint8_t)~(uint8_t)0xE0u; + /* MCG->C5: ??=0,PLLCLKEN=0,PLLSTEN=0,PRDIV0=0 */ + MCG->C5 = (uint8_t)0x00u; + /* MCG->C6: LOLIE=0,PLLS=0,CME=0,VDIV0=0 */ + MCG->C6 = (uint8_t)0x00u; + while((MCG->S & MCG_S_OSCINIT0_MASK) == 0u) { /* Check that the oscillator is running */ + } +#if 0 /* ARM: THIS CHECK IS REMOVED DUE TO BUG WITH SLOW IRC IN REV. 1.0 */ + while((MCG->S & MCG_S_IREFST_MASK) != 0u) { /* Check that the source of the FLL reference clock is the external reference clock. */ + } +#endif + while((MCG->S & 0x0CU) != 0x08u) { /* Wait until external reference clock is selected as MCG output */ + } + /* Switch to BLPE Mode */ + /* MCG->C2: ??=0,??=0,RANGE0=2,HGO=0,EREFS=1,LP=0,IRCS=0 */ + MCG->C2 = (uint8_t)0x24u; +#endif /* (CLOCK_SETUP == 2) */ +} + +/* ---------------------------------------------------------------------------- + -- SystemCoreClockUpdate() + ---------------------------------------------------------------------------- */ + +void SystemCoreClockUpdate (void) { + uint32_t MCGOUTClock; /* Variable to store output clock frequency of the MCG module */ + uint8_t Divider; + + if ((MCG->C1 & MCG_C1_CLKS_MASK) == 0x0u) { + /* Output of FLL or PLL is selected */ + if ((MCG->C6 & MCG_C6_PLLS_MASK) == 0x0u) { + /* FLL is selected */ + if ((MCG->C1 & MCG_C1_IREFS_MASK) == 0x0u) { + /* External reference clock is selected */ + if ((MCG->C7 & MCG_C7_OSCSEL_MASK) == 0x0u) { + MCGOUTClock = CPU_XTAL_CLK_HZ; /* System oscillator drives MCG clock */ + } else { /* (!((MCG->C7 & MCG_C7_OSCSEL_MASK) == 0x0u)) */ + MCGOUTClock = CPU_XTAL32k_CLK_HZ; /* RTC 32 kHz oscillator drives MCG clock */ + } /* (!((MCG->C7 & MCG_C7_OSCSEL_MASK) == 0x0u)) */ + Divider = (uint8_t)(1u << ((MCG->C1 & MCG_C1_FRDIV_MASK) >> MCG_C1_FRDIV_SHIFT)); + MCGOUTClock = (MCGOUTClock / Divider); /* Calculate the divided FLL reference clock */ + if ((MCG->C2 & MCG_C2_RANGE0_MASK) != 0x0u) { + MCGOUTClock /= 32u; /* If high range is enabled, additional 32 divider is active */ + } /* ((MCG->C2 & MCG_C2_RANGE0_MASK) != 0x0u) */ + } else { /* (!((MCG->C1 & MCG_C1_IREFS_MASK) == 0x0u)) */ + MCGOUTClock = CPU_INT_SLOW_CLK_HZ; /* The slow internal reference clock is selected */ + } /* (!((MCG->C1 & MCG_C1_IREFS_MASK) == 0x0u)) */ + /* Select correct multiplier to calculate the MCG output clock */ + switch (MCG->C4 & (MCG_C4_DMX32_MASK | MCG_C4_DRST_DRS_MASK)) { + case 0x0u: + MCGOUTClock *= 640u; + break; + case 0x20u: + MCGOUTClock *= 1280u; + break; + case 0x40u: + MCGOUTClock *= 1920u; + break; + case 0x60u: + MCGOUTClock *= 2560u; + break; + case 0x80u: + MCGOUTClock *= 732u; + break; + case 0xA0u: + MCGOUTClock *= 1464u; + break; + case 0xC0u: + MCGOUTClock *= 2197u; + break; + case 0xE0u: + MCGOUTClock *= 2929u; + break; + default: + break; + } + } else { /* (!((MCG->C6 & MCG_C6_PLLS_MASK) == 0x0u)) */ + /* PLL is selected */ + Divider = (1u + (MCG->C5 & MCG_C5_PRDIV0_MASK)); + MCGOUTClock = (uint32_t)(CPU_XTAL_CLK_HZ / Divider); /* Calculate the PLL reference clock */ + Divider = ((MCG->C6 & MCG_C6_VDIV0_MASK) + 24u); + MCGOUTClock *= Divider; /* Calculate the MCG output clock */ + } /* (!((MCG->C6 & MCG_C6_PLLS_MASK) == 0x0u)) */ + } else if ((MCG->C1 & MCG_C1_CLKS_MASK) == 0x40u) { + /* Internal reference clock is selected */ + if ((MCG->C2 & MCG_C2_IRCS_MASK) == 0x0u) { + MCGOUTClock = CPU_INT_SLOW_CLK_HZ; /* Slow internal reference clock selected */ + } else { /* (!((MCG->C2 & MCG_C2_IRCS_MASK) == 0x0u)) */ + MCGOUTClock = CPU_INT_FAST_CLK_HZ / (1 << ((MCG->SC & MCG_SC_FCRDIV_MASK) >> MCG_SC_FCRDIV_SHIFT)); /* Fast internal reference clock selected */ + } /* (!((MCG->C2 & MCG_C2_IRCS_MASK) == 0x0u)) */ + } else if ((MCG->C1 & MCG_C1_CLKS_MASK) == 0x80u) { + /* External reference clock is selected */ + if ((MCG->C7 & MCG_C7_OSCSEL_MASK) == 0x0u) { + MCGOUTClock = CPU_XTAL_CLK_HZ; /* System oscillator drives MCG clock */ + } else { /* (!((MCG->C7 & MCG_C7_OSCSEL_MASK) == 0x0u)) */ + MCGOUTClock = CPU_XTAL32k_CLK_HZ; /* RTC 32 kHz oscillator drives MCG clock */ + } /* (!((MCG->C7 & MCG_C7_OSCSEL_MASK) == 0x0u)) */ + } else { /* (!((MCG->C1 & MCG_C1_CLKS_MASK) == 0x80u)) */ + /* Reserved value */ + return; + } /* (!((MCG->C1 & MCG_C1_CLKS_MASK) == 0x80u)) */ + SystemCoreClock = (MCGOUTClock / (1u + ((SIM->CLKDIV1 & SIM_CLKDIV1_OUTDIV1_MASK) >> SIM_CLKDIV1_OUTDIV1_SHIFT))); +} diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/system_MK20D5.h b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/system_MK20D5.h new file mode 100644 index 0000000000..0396163f48 --- /dev/null +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/system_MK20D5.h @@ -0,0 +1,87 @@ +/* +** ################################################################### +** Compilers: ARM Compiler +** Freescale C/C++ for Embedded ARM +** GNU C Compiler +** IAR ANSI C/C++ Compiler for ARM +** +** Reference manuals: K20P64M50SF0RM Rev. 1, Oct 2011 +** K20P32M50SF0RM Rev. 1, Oct 2011 +** K20P48M50SF0RM Rev. 1, Oct 2011 +** +** Version: rev. 2.0, 2012-03-19 +** +** Abstract: +** Provides a system configuration function and a global variable that +** contains the system frequency. It configures the device and initializes +** the oscillator (PLL) that is part of the microcontroller device. +** +** Copyright: 2012 Freescale Semiconductor, Inc. All Rights Reserved. +** +** http: www.freescale.com +** mail: support@freescale.com +** +** Revisions: +** - rev. 1.0 (2011-12-15) +** Initial version +** - rev. 2.0 (2012-03-19) +** PDB Peripheral register structure updated. +** DMA Registers and bits for unsupported DMA channels removed. +** +** ################################################################### +*/ + +/** + * @file MK20D5 + * @version 2.0 + * @date 2012-03-19 + * @brief Device specific configuration file for MK20D5 (header file) + * + * Provides a system configuration function and a global variable that contains + * the system frequency. It configures the device and initializes the oscillator + * (PLL) that is part of the microcontroller device. + */ + +#ifndef SYSTEM_MK20D5_H_ +#define SYSTEM_MK20D5_H_ /**< Symbol preventing repeated inclusion */ + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +/** + * @brief System clock frequency (core clock) + * + * The system clock frequency supplied to the SysTick timer and the processor + * core clock. This variable can be used by the user application to setup the + * SysTick timer or configure other parameters. It may also be used by debugger to + * query the frequency of the debug timer or configure the trace clock speed + * SystemCoreClock is initialized with a correct predefined value. + */ +extern uint32_t SystemCoreClock; + +/** + * @brief Setup the microcontroller system. + * + * Typically this function configures the oscillator (PLL) that is part of the + * microcontroller device. For systems with variable clock speed it also updates + * the variable SystemCoreClock. SystemInit is called from startup_device file. + */ +void SystemInit (void); + +/** + * @brief Updates the SystemCoreClock variable. + * + * It must be called whenever the core clock is changed during program + * execution. SystemCoreClockUpdate() evaluates the clock register settings and calculates + * the current core clock. + */ +void SystemCoreClockUpdate (void); + +#ifdef __cplusplus +} +#endif + +#endif /* #if !defined(SYSTEM_MK20D5_H_) */ diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PeripheralNames.h b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PeripheralNames.h new file mode 100644 index 0000000000..ca406812e3 --- /dev/null +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PeripheralNames.h @@ -0,0 +1,89 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2013 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#ifndef MBED_PERIPHERALNAMES_H +#define MBED_PERIPHERALNAMES_H + +#include "cmsis.h" + +#ifdef __cplusplus +extern "C" { +#endif + +typedef enum { + UART_0 = (int)UART0_BASE, + UART_1 = (int)UART1_BASE, + UART_2 = (int)UART2_BASE +} UARTName; +#define STDIO_UART_TX USBTX +#define STDIO_UART_RX USBRX +#define STDIO_UART UART_0 + +typedef enum { + I2C_0 = (int)I2C0_BASE, + //I2C_1 = (int)I2C1_BASE, +} I2CName; + +#define TPM_SHIFT 8 +typedef enum { + PWM_1 = (0 << TPM_SHIFT) | (0), // TPM0 CH0 + PWM_2 = (0 << TPM_SHIFT) | (1), // TPM0 CH1 + PWM_3 = (0 << TPM_SHIFT) | (2), // TPM0 CH2 + PWM_4 = (0 << TPM_SHIFT) | (3), // TPM0 CH3 + PWM_5 = (0 << TPM_SHIFT) | (4), // TPM0 CH4 + PWM_6 = (0 << TPM_SHIFT) | (5), // TPM0 CH5 + + PWM_7 = (1 << TPM_SHIFT) | (0), // TPM1 CH0 + PWM_8 = (1 << TPM_SHIFT) | (1), // TPM1 CH1 + + PWM_9 = (2 << TPM_SHIFT) | (0), // TPM2 CH0 + PWM_10 = (2 << TPM_SHIFT) | (1) // TPM2 CH1 +} PWMName; + +#define CHANNELS_A_SHIFT 5 +typedef enum { + ADC0_SE0 = 0, + ADC0_SE3 = 3, + ADC0_SE4a = (1 << CHANNELS_A_SHIFT) | (4), + ADC0_SE4b = 4, + ADC0_SE5b = 5, + ADC0_SE6b = 6, + ADC0_SE7a = (1 << CHANNELS_A_SHIFT) | (7), + ADC0_SE7b = 7, + ADC0_SE8 = 8, + ADC0_SE9 = 9, + ADC0_SE11 = 11, + ADC0_SE12 = 12, + ADC0_SE13 = 13, + ADC0_SE14 = 14, + ADC0_SE15 = 15, + ADC0_SE23 = 23 +} ADCName; + +typedef enum { + DAC_0 = 0 +} DACName; + + +typedef enum { + SPI_0 = (int)SPI0_BASE, + //SPI_1 = (int)SPI1_BASE, +} SPIName; + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PinNames.h b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PinNames.h new file mode 100644 index 0000000000..051b63a7c6 --- /dev/null +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PinNames.h @@ -0,0 +1,248 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2013 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#ifndef MBED_PINNAMES_H +#define MBED_PINNAMES_H + +#include "cmsis.h" + +#ifdef __cplusplus +extern "C" { +#endif + +typedef enum { + PIN_INPUT, + PIN_OUTPUT +} PinDirection; + +/* PCR - 0x1000 */ +#define PORT_SHIFT 12 + +typedef enum { + PTA0 = 0x0, + PTA1 = 0x4, + PTA2 = 0x8, + PTA3 = 0xc, + PTA4 = 0x10, + PTA5 = 0x14, + PTA6 = 0x18, + PTA7 = 0x1c, + PTA8 = 0x20, + PTA9 = 0x24, + PTA10 = 0x28, + PTA11 = 0x2c, + PTA12 = 0x30, + PTA13 = 0x34, + PTA14 = 0x38, + PTA15 = 0x3c, + PTA16 = 0x40, + PTA17 = 0x44, + PTA18 = 0x48, + PTA19 = 0x4c, + PTA20 = 0x50, + PTA21 = 0x54, + PTA22 = 0x58, + PTA23 = 0x5c, + PTA24 = 0x60, + PTA25 = 0x64, + PTA26 = 0x68, + PTA27 = 0x6c, + PTA28 = 0x70, + PTA29 = 0x74, + PTA30 = 0x78, + PTA31 = 0x7c, + PTB0 = 0x1000, + PTB1 = 0x1004, + PTB2 = 0x1008, + PTB3 = 0x100c, + PTB4 = 0x1010, + PTB5 = 0x1014, + PTB6 = 0x1018, + PTB7 = 0x101c, + PTB8 = 0x1020, + PTB9 = 0x1024, + PTB10 = 0x1028, + PTB11 = 0x102c, + PTB12 = 0x1030, + PTB13 = 0x1034, + PTB14 = 0x1038, + PTB15 = 0x103c, + PTB16 = 0x1040, + PTB17 = 0x1044, + PTB18 = 0x1048, + PTB19 = 0x104c, + PTB20 = 0x1050, + PTB21 = 0x1054, + PTB22 = 0x1058, + PTB23 = 0x105c, + PTB24 = 0x1060, + PTB25 = 0x1064, + PTB26 = 0x1068, + PTB27 = 0x106c, + PTB28 = 0x1070, + PTB29 = 0x1074, + PTB30 = 0x1078, + PTB31 = 0x107c, + PTC0 = 0x2000, + PTC1 = 0x2004, + PTC2 = 0x2008, + PTC3 = 0x200c, + PTC4 = 0x2010, + PTC5 = 0x2014, + PTC6 = 0x2018, + PTC7 = 0x201c, + PTC8 = 0x2020, + PTC9 = 0x2024, + PTC10 = 0x2028, + PTC11 = 0x202c, + PTC12 = 0x2030, + PTC13 = 0x2034, + PTC14 = 0x2038, + PTC15 = 0x203c, + PTC16 = 0x2040, + PTC17 = 0x2044, + PTC18 = 0x2048, + PTC19 = 0x204c, + PTC20 = 0x2050, + PTC21 = 0x2054, + PTC22 = 0x2058, + PTC23 = 0x205c, + PTC24 = 0x2060, + PTC25 = 0x2064, + PTC26 = 0x2068, + PTC27 = 0x206c, + PTC28 = 0x2070, + PTC29 = 0x2074, + PTC30 = 0x2078, + PTC31 = 0x207c, + PTD0 = 0x3000, + PTD1 = 0x3004, + PTD2 = 0x3008, + PTD3 = 0x300c, + PTD4 = 0x3010, + PTD5 = 0x3014, + PTD6 = 0x3018, + PTD7 = 0x301c, + PTD8 = 0x3020, + PTD9 = 0x3024, + PTD10 = 0x3028, + PTD11 = 0x302c, + PTD12 = 0x3030, + PTD13 = 0x3034, + PTD14 = 0x3038, + PTD15 = 0x303c, + PTD16 = 0x3040, + PTD17 = 0x3044, + PTD18 = 0x3048, + PTD19 = 0x304c, + PTD20 = 0x3050, + PTD21 = 0x3054, + PTD22 = 0x3058, + PTD23 = 0x305c, + PTD24 = 0x3060, + PTD25 = 0x3064, + PTD26 = 0x3068, + PTD27 = 0x306c, + PTD28 = 0x3070, + PTD29 = 0x3074, + PTD30 = 0x3078, + PTD31 = 0x307c, + PTE0 = 0x4000, + PTE1 = 0x4004, + PTE2 = 0x4008, + PTE3 = 0x400c, + PTE4 = 0x4010, + PTE5 = 0x4014, + PTE6 = 0x4018, + PTE7 = 0x401c, + PTE8 = 0x4020, + PTE9 = 0x4024, + PTE10 = 0x4028, + PTE11 = 0x402c, + PTE12 = 0x4030, + PTE13 = 0x4034, + PTE14 = 0x4038, + PTE15 = 0x403c, + PTE16 = 0x4040, + PTE17 = 0x4044, + PTE18 = 0x4048, + PTE19 = 0x404c, + PTE20 = 0x4050, + PTE21 = 0x4054, + PTE22 = 0x4058, + PTE23 = 0x405c, + PTE24 = 0x4060, + PTE25 = 0x4064, + PTE26 = 0x4068, + PTE27 = 0x406c, + PTE28 = 0x4070, + PTE29 = 0x4074, + PTE30 = 0x4078, + PTE31 = 0x407c, + + LED_RED = PTC3, + LED_GREEN = PTD4, + LED_BLUE = PTA2, + + // mbed original LED naming + LED1 = LED_BLUE, + LED2 = LED_GREEN, + LED3 = LED_RED, + LED4 = LED_RED, + + // USB Pins + USBTX = PTB1, + USBRX = PTB2, + + // Arduino Headers + D0 = PTE1, + D1 = PTE0, + D2 = PTA5, + D3 = PTD4, + D4 = PTC8, + D5 = PTA1, + D6 = PTC3, + D7 = PTC4, + D8 = PTA12, + D9 = PTA2, + D10 = PTC2, + D11 = PTD2, + D12 = PTD3, + D13 = PTD1, + D14 = PTB3, + D15 = PTB2, + + A0 = PTB0, + A1 = PTB1, + A2 = PTD5, + A3 = PTD6, + A4 = PTC1, + A5 = PTC0, + + // Not connected + NC = (int)0xFFFFFFFF +} PinName; + +/* PullDown not available for KL05 */ +typedef enum { + PullNone = 0, + PullUp = 2, +} PinMode; + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PortNames.h b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PortNames.h new file mode 100644 index 0000000000..84831863f3 --- /dev/null +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PortNames.h @@ -0,0 +1,34 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2013 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#ifndef MBED_PORTNAMES_H +#define MBED_PORTNAMES_H + +#ifdef __cplusplus +extern "C" { +#endif + +typedef enum { + PortA = 0, + PortB = 1, + PortC = 2, + PortD = 3, + PortE = 4 +} PortName; + +#ifdef __cplusplus +} +#endif +#endif diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/analogin_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/analogin_api.c new file mode 100644 index 0000000000..455fa835db --- /dev/null +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/analogin_api.c @@ -0,0 +1,94 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2013 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#include "analogin_api.h" + +#include "cmsis.h" +#include "pinmap.h" +#include "error.h" + +static const PinMap PinMap_ADC[] = { + {PTE20, ADC0_SE0, 0}, + {PTE22, ADC0_SE3, 0}, + {PTE21, ADC0_SE4a, 0}, + {PTE29, ADC0_SE4b, 0}, + {PTE30, ADC0_SE23, 0}, + {PTE23, ADC0_SE7a, 0}, + {PTB0, ADC0_SE8, 0}, + {PTB1, ADC0_SE9, 0}, + {PTB2, ADC0_SE12, 0}, + {PTB3, ADC0_SE13, 0}, + {PTC0, ADC0_SE14, 0}, + {PTC1, ADC0_SE15, 0}, + {PTC2, ADC0_SE11, 0}, + {PTD1, ADC0_SE5b, 0}, + {PTD5, ADC0_SE6b, 0}, + {PTD6, ADC0_SE7b, 0}, + {NC, NC, 0} +}; + +void analogin_init(analogin_t *obj, PinName pin) { + obj->adc = (ADCName)pinmap_peripheral(pin, PinMap_ADC); + if (obj->adc == (ADCName)NC) { + error("ADC pin mapping failed"); + } + + SIM->SCGC6 |= SIM_SCGC6_ADC0_MASK; + + uint32_t port = (uint32_t)pin >> PORT_SHIFT; + SIM->SCGC5 |= 1 << (SIM_SCGC5_PORTA_SHIFT + port); + + uint32_t cfg2_muxsel = ADC_CFG2_MUXSEL_MASK; + if (obj->adc & (1 << CHANNELS_A_SHIFT)) { + cfg2_muxsel = 0; + } + + ADC0->SC1[1] = ADC_SC1_ADCH(obj->adc & ~(1 << CHANNELS_A_SHIFT)); + + ADC0->CFG1 = ADC_CFG1_ADLPC_MASK // Low-Power Configuration + | ADC_CFG1_ADIV(3) // Clock Divide Select: (Input Clock)/8 + | ADC_CFG1_ADLSMP_MASK // Long Sample Time + | ADC_CFG1_MODE(3) // (16)bits Resolution + | ADC_CFG1_ADICLK(1); // Input Clock: (Bus Clock)/2 + + ADC0->CFG2 = cfg2_muxsel // ADxxb or ADxxa channels + | ADC_CFG2_ADACKEN_MASK // Asynchronous Clock Output Enable + | ADC_CFG2_ADHSC_MASK // High-Speed Configuration + | ADC_CFG2_ADLSTS(0); // Long Sample Time Select + + ADC0->SC2 = ADC_SC2_REFSEL(0); // Default Voltage Reference + + ADC0->SC3 = ADC_SC3_AVGE_MASK // Hardware Average Enable + | ADC_SC3_AVGS(0); // 4 Samples Averaged + + pinmap_pinout(pin, PinMap_ADC); +} + +uint16_t analogin_read_u16(analogin_t *obj) { + // start conversion + ADC0->SC1[0] = ADC_SC1_ADCH(obj->adc & ~(1 << CHANNELS_A_SHIFT)); + + // Wait Conversion Complete + while ((ADC0->SC1[0] & ADC_SC1_COCO_MASK) != ADC_SC1_COCO_MASK); + + // Return value + return (uint16_t)ADC0->R[0]; +} + +float analogin_read(analogin_t *obj) { + uint16_t value = analogin_read_u16(obj); + return (float)value * (1.0f / (float)0xFFFF); +} + diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/device.h b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/device.h new file mode 100644 index 0000000000..82374a0224 --- /dev/null +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/device.h @@ -0,0 +1,58 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2013 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#ifndef MBED_DEVICE_H +#define MBED_DEVICE_H + +#define DEVICE_PORTIN 1 +#define DEVICE_PORTOUT 1 +#define DEVICE_PORTINOUT 1 + +#define DEVICE_INTERRUPTIN 1 + +#define DEVICE_ANALOGIN 1 +#define DEVICE_ANALOGOUT 1 + +#define DEVICE_SERIAL 1 + +#define DEVICE_I2C 1 +#define DEVICE_I2CSLAVE 1 + +#define DEVICE_SPI 1 +#define DEVICE_SPISLAVE 1 + +#define DEVICE_CAN 0 + +#define DEVICE_RTC 1 + +#define DEVICE_ETHERNET 0 + +#define DEVICE_PWMOUT 1 + +#define DEVICE_SEMIHOST 1 +#define DEVICE_LOCALFILESYSTEM 0 +#define DEVICE_ID_LENGTH 24 + +#define DEVICE_SLEEP 0 + +#define DEVICE_DEBUG_AWARENESS 0 + +#define DEVICE_STDIO_MESSAGES 1 + +#define DEVICE_ERROR_RED 1 + +#include "objects.h" + +#endif diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_api.c new file mode 100644 index 0000000000..d039c57a05 --- /dev/null +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_api.c @@ -0,0 +1,54 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2013 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#include "gpio_api.h" +#include "pinmap.h" + +uint32_t gpio_set(PinName pin) { + pin_function(pin, 1); + return 1 << ((pin & 0x7F) >> 2); +} + +void gpio_init(gpio_t *obj, PinName pin, PinDirection direction) { + if(pin == NC) return; + + obj->pin = pin; + obj->mask = gpio_set(pin); + + unsigned int port = (unsigned int)pin >> PORT_SHIFT; + + GPIO_Type *reg = (GPIO_Type *)(PTA_BASE + port * 0x40); + obj->reg_set = ®->PSOR; + obj->reg_clr = ®->PCOR; + obj->reg_in = ®->PDIR; + obj->reg_dir = ®->PDDR; + + gpio_dir(obj, direction); + switch (direction) { + case PIN_OUTPUT: pin_mode(pin, PullNone); break; + case PIN_INPUT : pin_mode(pin, PullUp); break; + } +} + +void gpio_mode(gpio_t *obj, PinMode mode) { + pin_mode(obj->pin, mode); +} + +void gpio_dir(gpio_t *obj, PinDirection direction) { + switch (direction) { + case PIN_INPUT : *obj->reg_dir &= ~obj->mask; break; + case PIN_OUTPUT: *obj->reg_dir |= obj->mask; break; + } +} diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_irq_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_irq_api.c new file mode 100644 index 0000000000..a2aaf9c2d0 --- /dev/null +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_irq_api.c @@ -0,0 +1,145 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2013 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#include +#include "cmsis.h" + +#include "gpio_irq_api.h" +#include "error.h" + +#define CHANNEL_NUM 64 + +static uint32_t channel_ids[CHANNEL_NUM] = {0}; +static gpio_irq_handler irq_handler; + +#define IRQ_DISABLED (0) +#define IRQ_RAISING_EDGE PORT_PCR_IRQC(9) +#define IRQ_FALLING_EDGE PORT_PCR_IRQC(10) +#define IRQ_EITHER_EDGE PORT_PCR_IRQC(11) + +static void handle_interrupt_in(PORT_Type *port, int ch_base) { + uint32_t mask = 0, i; + + for (i = 0; i < 32; i++) { + uint32_t pmask = (1 << i); + if (port->ISFR & pmask) { + mask |= pmask; + uint32_t id = channel_ids[ch_base + i]; + if (id == 0) continue; + + GPIO_Type *gpio; + gpio_irq_event event = IRQ_NONE; + switch (port->PCR[i] & PORT_PCR_IRQC_MASK) { + case IRQ_RAISING_EDGE: + event = IRQ_RISE; + break; + + case IRQ_FALLING_EDGE: + event = IRQ_FALL; + break; + + case IRQ_EITHER_EDGE: + gpio = (port == PORTA) ? (PTA) : (PTD); + event = (gpio->PDIR & pmask) ? (IRQ_RISE) : (IRQ_FALL); + break; + } + if (event != IRQ_NONE) + irq_handler(id, event); + } + } + port->ISFR = mask; +} + +void gpio_irqA(void) {handle_interrupt_in(PORTA, 0);} +void gpio_irqD(void) {handle_interrupt_in(PORTD, 32);} + +int gpio_irq_init(gpio_irq_t *obj, PinName pin, gpio_irq_handler handler, uint32_t id) { + if (pin == NC) return -1; + + irq_handler = handler; + + obj->port = pin >> PORT_SHIFT; + obj->pin = (pin & 0x7F) >> 2; + + uint32_t ch_base, vector; + IRQn_Type irq_n; + switch (obj->port) { + case PortA: + ch_base = 0; irq_n = PORTA_IRQn; vector = (uint32_t)gpio_irqA; + break; + + case PortD: + ch_base = 32; irq_n = PORTD_IRQn; vector = (uint32_t)gpio_irqD; + break; + + default: + error("gpio_irq only supported on port A and D\n"); + break; + } + NVIC_SetVector(irq_n, vector); + NVIC_EnableIRQ(irq_n); + + obj->ch = ch_base + obj->pin; + channel_ids[obj->ch] = id; + + return 0; +} + +void gpio_irq_free(gpio_irq_t *obj) { + channel_ids[obj->ch] = 0; +} + +void gpio_irq_set(gpio_irq_t *obj, gpio_irq_event event, uint32_t enable) { + PORT_Type *port = (PORT_Type *)(PORTA_BASE + 0x1000 * obj->port); + + uint32_t irq_settings = IRQ_DISABLED; + + switch (port->PCR[obj->pin] & PORT_PCR_IRQC_MASK) { + case IRQ_DISABLED: + if (enable) { + irq_settings = (event == IRQ_RISE) ? (IRQ_RAISING_EDGE) : (IRQ_FALLING_EDGE); + } + break; + + case IRQ_RAISING_EDGE: + if (enable) { + irq_settings = (event == IRQ_RISE) ? (IRQ_RAISING_EDGE) : (IRQ_EITHER_EDGE); + } else { + if (event == IRQ_FALL) + irq_settings = IRQ_RAISING_EDGE; + } + break; + + case IRQ_FALLING_EDGE: + if (enable) { + irq_settings = (event == IRQ_FALL) ? (IRQ_FALLING_EDGE) : (IRQ_EITHER_EDGE); + } else { + if (event == IRQ_RISE) + irq_settings = IRQ_FALLING_EDGE; + } + break; + + case IRQ_EITHER_EDGE: + if (enable) { + irq_settings = IRQ_EITHER_EDGE; + } else { + irq_settings = (event == IRQ_RISE) ? (IRQ_FALLING_EDGE) : (IRQ_RAISING_EDGE); + } + break; + } + + // Interrupt configuration and clear interrupt + port->PCR[obj->pin] = (port->PCR[obj->pin] & ~PORT_PCR_IRQC_MASK) | irq_settings | PORT_PCR_ISF_MASK; +} diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_object.h b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_object.h new file mode 100644 index 0000000000..58c9d4b096 --- /dev/null +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_object.h @@ -0,0 +1,49 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2013 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#ifndef MBED_GPIO_OBJECT_H +#define MBED_GPIO_OBJECT_H + +#ifdef __cplusplus +extern "C" { +#endif + +typedef struct { + PinName pin; + uint32_t mask; + + __IO uint32_t *reg_dir; + __IO uint32_t *reg_set; + __IO uint32_t *reg_clr; + __I uint32_t *reg_in; +} gpio_t; + +static inline void gpio_write(gpio_t *obj, int value) { + if (value) { + *obj->reg_set = obj->mask; + } else { + *obj->reg_clr = obj->mask; + } +} + +static inline int gpio_read(gpio_t *obj) { + return ((*obj->reg_in & obj->mask) ? 1 : 0); +} + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/i2c_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/i2c_api.c new file mode 100644 index 0000000000..27a3b734a1 --- /dev/null +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/i2c_api.c @@ -0,0 +1,423 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2013 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#include "i2c_api.h" + +#include "cmsis.h" +#include "pinmap.h" +#include "error.h" + +static const PinMap PinMap_I2C_SDA[] = { + {PTE25, I2C_0, 5}, + {PTC9, I2C_0, 2}, + {PTE0, I2C_0, 6}, + {PTB1, I2C_0, 2}, + {PTB3, I2C_0, 2}, + {PTC11, I2C_0, 2}, + {PTC2, I2C_0, 2}, + {PTA4, I2C_0, 2}, + {NC , NC , 0} +}; + +static const PinMap PinMap_I2C_SCL[] = { + {PTE24, I2C_0, 5}, + {PTC8, I2C_0, 2}, + {PTE1, I2C_0, 6}, + {PTB0, I2C_0, 2}, + {PTB2, I2C_0, 2}, + {PTC10, I2C_0, 2}, + {PTC1, I2C_0, 2}, + {NC , NC, 0} +}; + +static const uint16_t ICR[0x40] = { + 20, 22, 24, 26, 28, + 30, 34, 40, 28, 32, + 36, 40, 44, 48, 56, + 68, 48, 56, 64, 72, + 80, 88, 104, 128, 80, + 96, 112, 128, 144, 160, + 192, 240, 160, 192, 224, + 256, 288, 320, 384, 480, + 320, 384, 448, 512, 576, + 640, 768, 960, 640, 768, + 896, 1024, 1152, 1280, 1536, + 1920, 1280, 1536, 1792, 2048, + 2304, 2560, 3072, 3840 +}; + +static uint8_t first_read; + + +void i2c_init(i2c_t *obj, PinName sda, PinName scl) { + // determine the I2C to use + I2CName i2c_sda = (I2CName)pinmap_peripheral(sda, PinMap_I2C_SDA); + I2CName i2c_scl = (I2CName)pinmap_peripheral(scl, PinMap_I2C_SCL); + obj->i2c = (I2C_Type*)pinmap_merge(i2c_sda, i2c_scl); + if ((int)obj->i2c == NC) { + error("I2C pin mapping failed"); + } + + // enable power + switch ((int)obj->i2c) { + case I2C_0: SIM->SCGC5 |= 1 << 13; SIM->SCGC4 |= 1 << 6; break; + //case I2C_1: SIM->SCGC5 |= 1 << 11; SIM->SCGC4 |= 1 << 7; break; + } + + // set default frequency at 100k + i2c_frequency(obj, 100000); + + // enable I2C interface + obj->i2c->C1 |= 0x80; + + pinmap_pinout(sda, PinMap_I2C_SDA); + pinmap_pinout(scl, PinMap_I2C_SCL); + + first_read = 1; +} + +int i2c_start(i2c_t *obj) { + uint8_t temp; + volatile int i; + // if we are in the middle of a transaction + // activate the repeat_start flag + if (obj->i2c->S & I2C_S_BUSY_MASK) { + // KL25Z errata sheet: repeat start cannot be generated if the + // I2Cx_F[MULT] field is set to a non-zero value + temp = obj->i2c->F >> 6; + obj->i2c->F &= 0x3F; + obj->i2c->C1 |= 0x04; + for (i = 0; i < 100; i ++) __NOP(); + obj->i2c->F |= temp << 6; + } else { + obj->i2c->C1 |= I2C_C1_MST_MASK; + obj->i2c->C1 |= I2C_C1_TX_MASK; + } + first_read = 1; + return 0; +} + +int i2c_stop(i2c_t *obj) { + volatile uint32_t n = 0; + obj->i2c->C1 &= ~I2C_C1_MST_MASK; + obj->i2c->C1 &= ~I2C_C1_TX_MASK; + + // It seems that there are timing problems + // when there is no waiting time after a STOP. + // This wait is also included on the samples + // code provided with the freedom board + for (n = 0; n < 100; n++) __NOP(); + first_read = 1; + return 0; +} + +static int timeout_status_poll(i2c_t *obj, uint32_t mask) { + uint32_t i, timeout = 1000; + + for (i = 0; i < timeout; i++) { + if (obj->i2c->S & mask) + return 0; + } + + return 1; +} + +// this function waits the end of a tx transfer and return the status of the transaction: +// 0: OK ack received +// 1: OK ack not received +// 2: failure +static int i2c_wait_end_tx_transfer(i2c_t *obj) { + + // wait for the interrupt flag + if (timeout_status_poll(obj, I2C_S_IICIF_MASK)) { + return 2; + } + + obj->i2c->S |= I2C_S_IICIF_MASK; + + // wait transfer complete + if (timeout_status_poll(obj, I2C_S_TCF_MASK)) { + return 2; + } + + // check if we received the ACK or not + return obj->i2c->S & I2C_S_RXAK_MASK ? 1 : 0; +} + +// this function waits the end of a rx transfer and return the status of the transaction: +// 0: OK +// 1: failure +static int i2c_wait_end_rx_transfer(i2c_t *obj) { + // wait for the end of the rx transfer + if (timeout_status_poll(obj, I2C_S_IICIF_MASK)) { + return 1; + } + + obj->i2c->S |= I2C_S_IICIF_MASK; + + return 0; +} + +static void i2c_send_nack(i2c_t *obj) { + obj->i2c->C1 |= I2C_C1_TXAK_MASK; // NACK +} + +static void i2c_send_ack(i2c_t *obj) { + obj->i2c->C1 &= ~I2C_C1_TXAK_MASK; // ACK +} + +static int i2c_do_write(i2c_t *obj, int value) { + // write the data + obj->i2c->D = value; + + // init and wait the end of the transfer + return i2c_wait_end_tx_transfer(obj); +} + +static int i2c_do_read(i2c_t *obj, char * data, int last) { + if (last) + i2c_send_nack(obj); + else + i2c_send_ack(obj); + + *data = (obj->i2c->D & 0xFF); + + // start rx transfer and wait the end of the transfer + return i2c_wait_end_rx_transfer(obj); +} + +void i2c_frequency(i2c_t *obj, int hz) { + uint8_t icr = 0; + uint8_t mult = 0; + uint32_t error = 0; + uint32_t p_error = 0xffffffff; + uint32_t ref = 0; + uint8_t i, j; + // bus clk + uint32_t PCLK = 24000000u; + uint32_t pulse = PCLK / (hz * 2); + + // we look for the values that minimize the error + + // test all the MULT values + for (i = 1; i < 5; i*=2) { + for (j = 0; j < 0x40; j++) { + ref = PCLK / (i*ICR[j]); + if (ref > (uint32_t)hz) + continue; + error = hz - ref; + if (error < p_error) { + icr = j; + mult = i/2; + p_error = error; + } + } + } + pulse = icr | (mult << 6); + + // I2C Rate + obj->i2c->F = pulse; +} + +int i2c_read(i2c_t *obj, int address, char *data, int length, int stop) { + int count; + char dummy_read, *ptr; + + if (i2c_start(obj)) { + i2c_stop(obj); + return I2C_ERROR_BUS_BUSY; + } + + if (i2c_do_write(obj, (address | 0x01))) { + i2c_stop(obj); + return I2C_ERROR_NO_SLAVE; + } + + // set rx mode + obj->i2c->C1 &= ~I2C_C1_TX_MASK; + + // Read in bytes + for (count = 0; count < (length); count++) { + ptr = (count == 0) ? &dummy_read : &data[count - 1]; + uint8_t stop_ = (count == (length - 1)) ? 1 : 0; + if (i2c_do_read(obj, ptr, stop_)) { + i2c_stop(obj); + return count; + } + } + + // If not repeated start, send stop. + if (stop) { + i2c_stop(obj); + } + + // last read + data[count-1] = obj->i2c->D; + + return length; +} +int i2c_write(i2c_t *obj, int address, const char *data, int length, int stop) { + int i; + + if (i2c_start(obj)) { + i2c_stop(obj); + return I2C_ERROR_BUS_BUSY; + } + + if (i2c_do_write(obj, (address & 0xFE))) { + i2c_stop(obj); + return I2C_ERROR_NO_SLAVE; + } + + for (i = 0; i < length; i++) { + if(i2c_do_write(obj, data[i])) { + i2c_stop(obj); + return i; + } + } + + if (stop) { + i2c_stop(obj); + } + + return length; +} + +void i2c_reset(i2c_t *obj) { + i2c_stop(obj); +} + +int i2c_byte_read(i2c_t *obj, int last) { + char data; + + // set rx mode + obj->i2c->C1 &= ~I2C_C1_TX_MASK; + + if(first_read) { + // first dummy read + i2c_do_read(obj, &data, 0); + first_read = 0; + } + + if (last) { + // set tx mode + obj->i2c->C1 |= I2C_C1_TX_MASK; + return obj->i2c->D; + } + + i2c_do_read(obj, &data, last); + + return data; +} + +int i2c_byte_write(i2c_t *obj, int data) { + first_read = 1; + + // set tx mode + obj->i2c->C1 |= I2C_C1_TX_MASK; + + return !i2c_do_write(obj, (data & 0xFF)); +} + + +#if DEVICE_I2CSLAVE +void i2c_slave_mode(i2c_t *obj, int enable_slave) { + if (enable_slave) { + // set slave mode + obj->i2c->C1 &= ~I2C_C1_MST_MASK; + obj->i2c->C1 |= I2C_C1_IICIE_MASK; + } else { + // set master mode + obj->i2c->C1 |= I2C_C1_MST_MASK; + } +} + +int i2c_slave_receive(i2c_t *obj) { + switch(obj->i2c->S) { + // read addressed + case 0xE6: return 1; + + // write addressed + case 0xE2: return 3; + + default: return 0; + } +} + +int i2c_slave_read(i2c_t *obj, char *data, int length) { + uint8_t dummy_read; + uint8_t * ptr; + int count; + + // set rx mode + obj->i2c->C1 &= ~I2C_C1_TX_MASK; + + // first dummy read + dummy_read = obj->i2c->D; + if(i2c_wait_end_rx_transfer(obj)) { + return 0; + } + + // read address + dummy_read = obj->i2c->D; + if(i2c_wait_end_rx_transfer(obj)) { + return 0; + } + + // read (length - 1) bytes + for (count = 0; count < (length - 1); count++) { + data[count] = obj->i2c->D; + if(i2c_wait_end_rx_transfer(obj)) { + return count; + } + } + + // read last byte + ptr = (length == 0) ? &dummy_read : (uint8_t *)&data[count]; + *ptr = obj->i2c->D; + + return (length) ? (count + 1) : 0; +} + +int i2c_slave_write(i2c_t *obj, const char *data, int length) { + int i, count = 0; + + // set tx mode + obj->i2c->C1 |= I2C_C1_TX_MASK; + + for (i = 0; i < length; i++) { + if(i2c_do_write(obj, data[count++]) == 2) { + return i; + } + } + + // set rx mode + obj->i2c->C1 &= ~I2C_C1_TX_MASK; + + // dummy rx transfer needed + // otherwise the master cannot generate a stop bit + obj->i2c->D; + if(i2c_wait_end_rx_transfer(obj) == 2) { + return count; + } + + return count; +} + +void i2c_slave_address(i2c_t *obj, int idx, uint32_t address, uint32_t mask) { + obj->i2c->A1 = address & 0xfe; +} +#endif + diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/objects.h b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/objects.h new file mode 100644 index 0000000000..30f428c187 --- /dev/null +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/objects.h @@ -0,0 +1,75 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2013 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#ifndef MBED_OBJECTS_H +#define MBED_OBJECTS_H + +#include "cmsis.h" +#include "PortNames.h" +#include "PeripheralNames.h" +#include "PinNames.h" + +#ifdef __cplusplus +extern "C" { +#endif + +struct gpio_irq_s { + uint32_t port; + uint32_t pin; + uint32_t ch; +}; + +struct port_s { + __IO uint32_t *reg_dir; + __IO uint32_t *reg_out; + __I uint32_t *reg_in; + PortName port; + uint32_t mask; +}; + +struct pwmout_s { + __IO uint32_t *MOD; + __IO uint32_t *CNT; + __IO uint32_t *CnV; +}; + +struct serial_s { + UART_Type *uart; + int index; +}; + +struct analogin_s { + ADCName adc; +}; + +struct dac_s { + DACName dac; +}; + +struct i2c_s { + I2C_Type *i2c; +}; + +struct spi_s { + SPI_Type *spi; +}; + +#include "gpio_object.h" + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pinmap.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pinmap.c new file mode 100644 index 0000000000..9bb5c3f220 --- /dev/null +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pinmap.c @@ -0,0 +1,39 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2013 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#include "pinmap.h" +#include "error.h" + +void pin_function(PinName pin, int function) { + if (pin == (PinName)NC) return; + + uint32_t port_n = (uint32_t)pin >> PORT_SHIFT; + uint32_t pin_n = (uint32_t)(pin & 0x7C) >> 2; + + SIM->SCGC5 |= 1 << (SIM_SCGC5_PORTA_SHIFT + port_n); + __IO uint32_t* pin_pcr = &(((PORT_Type *)(PORTA_BASE + 0x1000 * port_n)))->PCR[pin_n]; + + // pin mux bits: [10:8] -> 11100000000 = (0x700) + *pin_pcr = (*pin_pcr & ~0x700) | (function << 8); +} + +void pin_mode(PinName pin, PinMode mode) { + if (pin == (PinName)NC) { return; } + + __IO uint32_t* pin_pcr = (__IO uint32_t*)(PORTA_BASE + pin); + + // pin pullup bits: [1:0] -> 11 = (0x3) + *pin_pcr = (*pin_pcr & ~0x3) | mode; +} diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/port_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/port_api.c new file mode 100644 index 0000000000..0598916da4 --- /dev/null +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/port_api.c @@ -0,0 +1,68 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2013 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#include "port_api.h" +#include "pinmap.h" +#include "gpio_api.h" + +PinName port_pin(PortName port, int pin_n) { + return (PinName)((port << PORT_SHIFT) | (pin_n << 2)); +} + +void port_init(port_t *obj, PortName port, int mask, PinDirection dir) { + obj->port = port; + obj->mask = mask; + + GPIO_Type *reg = (GPIO_Type *)(PTA_BASE + port * 0x40); + + obj->reg_out = ®->PDOR; + obj->reg_in = ®->PDIR; + obj->reg_dir = ®->PDDR; + + uint32_t i; + // The function is set per pin: reuse gpio logic + for (i=0; i<32; i++) { + if (obj->mask & (1<port, i)); + } + } + + port_dir(obj, dir); +} + +void port_mode(port_t *obj, PinMode mode) { + uint32_t i; + // The mode is set per pin: reuse pinmap logic + for (i=0; i<32; i++) { + if (obj->mask & (1<port, i), mode); + } + } +} + +void port_dir(port_t *obj, PinDirection dir) { + switch (dir) { + case PIN_INPUT : *obj->reg_dir &= ~obj->mask; break; + case PIN_OUTPUT: *obj->reg_dir |= obj->mask; break; + } +} + +void port_write(port_t *obj, int value) { + *obj->reg_out = (*obj->reg_in & ~obj->mask) | (value & obj->mask); +} + +int port_read(port_t *obj) { + return (*obj->reg_in & obj->mask); +} diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pwmout_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pwmout_api.c new file mode 100644 index 0000000000..1168fb9c67 --- /dev/null +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pwmout_api.c @@ -0,0 +1,142 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2013 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#include "pwmout_api.h" + +#include "cmsis.h" +#include "pinmap.h" +#include "error.h" + +static const PinMap PinMap_PWM[] = { + // LEDs + {LED_RED , PWM_9 , 3}, // PTB18, FTM2 CH0 + {LED_GREEN, PWM_10, 3}, // PTB19, FTM2 CH1 + {LED_BLUE , PWM_2 , 4}, // PTD1 , FTM0 CH1 + + // Arduino digital pinout + {D0, PWM_9 , 3}, // PTA1 , FTM2 CH0 + {D1, PWM_10, 3}, // PTA2 , FTM2 CH1 + {D2, PWM_5 , 4}, // PTD4 , FTM0 CH4 + {D3, PWM_7 , 3}, // PTA12, FTM1 CH0 + {D4, PWM_2 , 3}, // PTA4 , FTM0 CH1 + {D5, PWM_3 , 3}, // PTA5 , FTM0 CH2 + {D6, PWM_5 , 3}, // PTC8 , FTM0 CH4 + {D7, PWM_6 , 3}, // PTC9 , FTM0 CH5 + {D8, PWM_8 , 3}, // PTA13, FTM1 CH1 + {D9, PWM_6 , 4}, // PTD5 , FTM0 CH5 + {D10, PWM_1 , 4}, // PTD0 , FTM0 CH0 + {D11, PWM_3 , 4}, // PTD2 , FTM0 CH2 + {D12, PWM_4 , 4}, // PTD3 , FTM0 CH3 + {D13, PWM_2 , 4}, // PTD1 , FTM0 CH1, + + {PTA0, PWM_6, 3}, + {PTA3, PWM_1, 3}, + {PTB0, PWM_7, 3}, + {PTB1, PWM_8, 3}, + {PTB2, PWM_9, 3}, + {PTB3, PWM_10, 3}, + {PTC1, PWM_1, 4}, + {PTC2, PWM_2, 4}, + {PTC3, PWM_3, 4}, + {PTC4, PWM_4, 4}, + {PTE20, PWM_7, 3}, + {PTE21, PWM_8, 3}, + {PTE22, PWM_9, 3}, + {PTE23, PWM_10, 3}, + {PTE24, PWM_1, 3}, + {PTE25, PWM_2, 3}, + {PTE29, PWM_3, 3}, + {PTE30, PWM_4, 3}, + {PTE31, PWM_5, 3}, + + {NC , NC , 0} +}; + +#define PWM_CLOCK_MHZ (0.75) // (48)MHz / 64 = (0.75)MHz + +void pwmout_init(pwmout_t* obj, PinName pin) { + // determine the channel + PWMName pwm = (PWMName)pinmap_peripheral(pin, PinMap_PWM); + if (pwm == (PWMName)NC) + error("PwmOut pin mapping failed"); + + unsigned int port = (unsigned int)pin >> PORT_SHIFT; + unsigned int ftm_n = (pwm >> TPM_SHIFT); + unsigned int ch_n = (pwm & 0xFF); + + SIM->SCGC5 |= 1 << (SIM_SCGC5_PORTA_SHIFT + port); + SIM->SCGC6 |= 1 << (SIM_SCGC6_FTM0_SHIFT + ftm_n); + SIM->SOPT2 |= SIM_SOPT2_CLKOUTSEL(1); // Clock source: MCGFLLCLK or MCGPLLCLK + + FTM_Type *ftm = (FTM_Type *)(FTM0_BASE + 0x1000 * ftm_n); + ftm->SC = FTM_SC_CLKS(1) | FTM_SC_PS(6); // (48)MHz / 64 = (0.75)MHz + ftm->CONTROLS[ch_n].CnSC = (FTM_CnSC_MSB_MASK | FTM_CnSC_ELSB_MASK); /* No Interrupts; High True pulses on Edge Aligned PWM */ + + obj->CnV = &ftm->CONTROLS[ch_n].CnV; + obj->MOD = &ftm->MOD; + obj->CNT = &ftm->CNT; + + // default to 20ms: standard for servos, and fine for e.g. brightness control + pwmout_period_ms(obj, 20); + pwmout_write (obj, 0); + + // Wire pinout + pinmap_pinout(pin, PinMap_PWM); +} + +void pwmout_free(pwmout_t* obj) {} + +void pwmout_write(pwmout_t* obj, float value) { + if (value < 0.0) { + value = 0.0; + } else if (value > 1.0) { + value = 1.0; + } + + *obj->CnV = (uint32_t)((float)(*obj->MOD) * value); + *obj->CNT = 0; +} + +float pwmout_read(pwmout_t* obj) { + float v = (float)(*obj->CnV) / (float)(*obj->MOD); + return (v > 1.0) ? (1.0) : (v); +} + +void pwmout_period(pwmout_t* obj, float seconds) { + pwmout_period_us(obj, seconds * 1000000.0f); +} + +void pwmout_period_ms(pwmout_t* obj, int ms) { + pwmout_period_us(obj, ms * 1000); +} + +// Set the PWM period, keeping the duty cycle the same. +void pwmout_period_us(pwmout_t* obj, int us) { + float dc = pwmout_read(obj); + *obj->MOD = PWM_CLOCK_MHZ * us; + pwmout_write(obj, dc); +} + +void pwmout_pulsewidth(pwmout_t* obj, float seconds) { + pwmout_pulsewidth_us(obj, seconds * 1000000.0f); +} + +void pwmout_pulsewidth_ms(pwmout_t* obj, int ms) { + pwmout_pulsewidth_us(obj, ms * 1000); +} + +void pwmout_pulsewidth_us(pwmout_t* obj, int us) { + *obj->CnV = PWM_CLOCK_MHZ * us; +} diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/rtc_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/rtc_api.c new file mode 100644 index 0000000000..0402f585bd --- /dev/null +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/rtc_api.c @@ -0,0 +1,91 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2013 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#include "rtc_api.h" + +static void init(void) { + // enable PORTC clock + SIM->SCGC5 |= SIM_SCGC5_PORTC_MASK; + + // enable RTC clock + SIM->SCGC6 |= SIM_SCGC6_RTC_MASK; + + /* + * configure PTC1 with alternate function 1: RTC_CLKIN + * As the kl25z board does not have a 32kHz osc, + * we use an external clock generated by the + * interface chip + */ + PORTC->PCR[1] &= ~PORT_PCR_MUX_MASK; + PORTC->PCR[1] = PORT_PCR_MUX(1); + + // select RTC_CLKIN as RTC clock source + SIM->SOPT1 &= ~SIM_SOPT1_OSC32KSEL_MASK; + SIM->SOPT1 |= SIM_SOPT1_OSC32KSEL(2); +} + +void rtc_init(void) { + init(); + + //Configure the TSR. default value: 1 + RTC->TSR = 1; + + // enable counter + RTC->SR |= RTC_SR_TCE_MASK; +} + +void rtc_free(void) { + // [TODO] +} + +/* + * Little check routine to see if the RTC has been enabled + * 0 = Disabled, 1 = Enabled + */ +int rtc_isenabled(void) { + // even if the RTC module is enabled, + // as we use RTC_CLKIN and an external clock, + // we need to reconfigure the pins. That is why we + // call init() if the rtc is enabled + + // if RTC not enabled return 0 + SIM->SCGC5 |= SIM_SCGC5_PORTC_MASK; + SIM->SCGC6 |= SIM_SCGC6_RTC_MASK; + if ((RTC->SR & RTC_SR_TCE_MASK) == 0) + return 0; + + init(); + return 1; +} + +time_t rtc_read(void) { + return RTC->TSR; +} + +void rtc_write(time_t t) { + // disable counter + RTC->SR &= ~RTC_SR_TCE_MASK; + + // we do not write 0 into TSR + // to avoid invalid time + if (t == 0) + t = 1; + + // write seconds + RTC->TSR = t; + + // re-enable counter + RTC->SR |= RTC_SR_TCE_MASK; +} diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/serial_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/serial_api.c new file mode 100644 index 0000000000..d72c6ace91 --- /dev/null +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/serial_api.c @@ -0,0 +1,303 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2013 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#include "serial_api.h" + +// math.h required for floating point operations for baud rate calculation +#include + +#include + +#include "cmsis.h" +#include "pinmap.h" +#include "error.h" + +/****************************************************************************** + * INITIALIZATION + ******************************************************************************/ +static const PinMap PinMap_UART_TX[] = { + {PTC4, UART_1, 3}, + {PTA2, UART_0, 2}, + {PTD5, UART_2, 3}, + {PTD3, UART_2, 3}, + {PTD7, UART_0, 3}, + {PTE20, UART_0, 4}, + {PTE22, UART_2, 4}, + {PTE0, UART_1, 3}, + {NC , NC , 0} +}; + +static const PinMap PinMap_UART_RX[] = { + {PTC3, UART_1, 3}, + {PTA1, UART_0, 2}, + {PTD4, UART_2, 3}, + {PTD2, UART_2, 3}, + {PTD6, UART_0, 3}, + {PTE23, UART_2, 4}, + {PTE21, UART_0, 4}, + {PTE1, UART_1, 3}, + {NC , NC , 0} +}; + +#define UART_NUM 3 +static uint32_t serial_irq_ids[UART_NUM] = {0}; +static uart_irq_handler irq_handler; + +int stdio_uart_inited = 0; +serial_t stdio_uart; + +void serial_init(serial_t *obj, PinName tx, PinName rx) { + // determine the UART to use + UARTName uart_tx = (UARTName)pinmap_peripheral(tx, PinMap_UART_TX); + UARTName uart_rx = (UARTName)pinmap_peripheral(rx, PinMap_UART_RX); + UARTName uart = (UARTName)pinmap_merge(uart_tx, uart_rx); + if ((int)uart == NC) { + error("Serial pinout mapping failed"); + } + + obj->uart = (UART_Type *)uart; + // enable clk + switch (uart) { + case UART_0: SIM->SOPT2 |= SIM_SOPT2_PLLFLLSEL_MASK | (1<SCGC5 |= SIM_SCGC5_PORTA_MASK; SIM->SCGC4 |= SIM_SCGC4_UART0_MASK; break; + case UART_1: SIM->SCGC5 |= SIM_SCGC5_PORTC_MASK; SIM->SCGC4 |= SIM_SCGC4_UART1_MASK; break; + case UART_2: SIM->SCGC5 |= SIM_SCGC5_PORTD_MASK; SIM->SCGC4 |= SIM_SCGC4_UART2_MASK; break; + } + // Disable UART before changing registers + obj->uart->C2 &= ~(UART_C2_RE_MASK | UART_C2_TE_MASK); + + switch (uart) { + case UART_0: obj->index = 0; break; + case UART_1: obj->index = 1; break; + case UART_2: obj->index = 2; break; + } + + // set default baud rate and format + serial_baud (obj, 9600); + serial_format(obj, 8, ParityNone, 1); + + // pinout the chosen uart + pinmap_pinout(tx, PinMap_UART_TX); + pinmap_pinout(rx, PinMap_UART_RX); + + // set rx/tx pins in PullUp mode + pin_mode(tx, PullUp); + pin_mode(rx, PullUp); + + obj->uart->C2 |= (UART_C2_RE_MASK | UART_C2_TE_MASK); + + if (uart == STDIO_UART) { + stdio_uart_inited = 1; + memcpy(&stdio_uart, obj, sizeof(serial_t)); + } +} + +void serial_free(serial_t *obj) { + serial_irq_ids[obj->index] = 0; +} + +// serial_baud +// +// set the baud rate, taking in to account the current SystemFrequency +// +// The LPC2300 and LPC1700 have a divider and a fractional divider to control the +// baud rate. The formula is: +// +// Baudrate = (1 / PCLK) * 16 * DL * (1 + DivAddVal / MulVal) +// where: +// 1 < MulVal <= 15 +// 0 <= DivAddVal < 14 +// DivAddVal < MulVal +// +void serial_baud(serial_t *obj, int baudrate) { + + // save C2 state + uint8_t c2_state = (obj->uart->C2 & (UART_C2_RE_MASK | UART_C2_TE_MASK)); + + // Disable UART before changing registers + obj->uart->C2 &= ~(UART_C2_RE_MASK | UART_C2_TE_MASK); + + // [TODO] not hardcode this value + uint32_t PCLK = (obj->uart == UART0) ? 48000000u : 24000000u; + + // First we check to see if the basic divide with no DivAddVal/MulVal + // ratio gives us an integer result. If it does, we set DivAddVal = 0, + // MulVal = 1. Otherwise, we search the valid ratio value range to find + // the closest match. This could be more elegant, using search methods + // and/or lookup tables, but the brute force method is not that much + // slower, and is more maintainable. + uint16_t DL = PCLK / (16 * baudrate); + + // set BDH and BDL + obj->uart->BDH = (obj->uart->BDH & ~(0x1f)) | ((DL >> 8) & 0x1f); + obj->uart->BDL = (obj->uart->BDL & ~(0xff)) | ((DL >> 0) & 0xff); + + // restore C2 state + obj->uart->C2 |= c2_state; +} + +void serial_format(serial_t *obj, int data_bits, SerialParity parity, int stop_bits) { + // uint8_t m10 = 0; + + // save C2 state + uint8_t c2_state = (obj->uart->C2 & (UART_C2_RE_MASK | UART_C2_TE_MASK)); + + // Disable UART before changing registers + obj->uart->C2 &= ~(UART_C2_RE_MASK | UART_C2_TE_MASK); + + // 8 data bits = 0 ... 9 data bits = 1 + if ((data_bits < 8) || (data_bits > 9)) { + error("Invalid number of bits (%d) in serial format, should be 8..9\r\n", data_bits); + } + data_bits -= 8; + + uint8_t parity_enable, parity_select; + switch (parity) { + case ParityNone: parity_enable = 0; parity_select = 0; break; + case ParityOdd : parity_enable = 1; parity_select = 1; data_bits++; break; + case ParityEven: parity_enable = 1; parity_select = 0; data_bits++; break; + default: + error("Invalid serial parity setting\r\n"); + return; + } + + // 1 stop bits = 0, 2 stop bits = 1 + if ((stop_bits != 1) && (stop_bits != 2)) { + error("Invalid stop bits specified\r\n"); + } + stop_bits -= 1; + + // 9 data bits + parity + if (data_bits == 2) { + // only uart0 supports 10 bit communication + if (obj->index != 0) { + error("Invalid number of bits (9) to be used with parity\r\n"); + } + data_bits = 0; + //m10 = 1; + } + + // data bits, parity and parity mode + obj->uart->C1 = ((data_bits << 4) + | (parity_enable << 1) + | (parity_select << 0)); + + // enable 10bit mode if needed + // if (obj->index == 0) { + // obj->uart->C4 &= ~UARTLP_C4_M10_MASK; + // obj->uart->C4 |= (m10 << UARTLP_C4_M10_SHIFT); + // } + + // stop bits + obj->uart->BDH &= ~UART_BDH_SBR_MASK; + obj->uart->BDH |= (stop_bits << UART_BDH_SBR_SHIFT); + + // restore C2 state + obj->uart->C2 |= c2_state; +} + +/****************************************************************************** + * INTERRUPTS HANDLING + ******************************************************************************/ +static inline void uart_irq(uint8_t status, uint32_t index) { + if (serial_irq_ids[index] != 0) { + if (status & UART_S1_TDRE_MASK) + irq_handler(serial_irq_ids[index], TxIrq); + + if (status & UART_S1_RDRF_MASK) + irq_handler(serial_irq_ids[index], RxIrq); + } +} + +void uart0_irq() {uart_irq(UART0->S1, 0);} +void uart1_irq() {uart_irq(UART1->S1, 1);} +void uart2_irq() {uart_irq(UART2->S1, 2);} + +void serial_irq_handler(serial_t *obj, uart_irq_handler handler, uint32_t id) { + irq_handler = handler; + serial_irq_ids[obj->index] = id; +} + +void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) { + IRQn_Type irq_n = (IRQn_Type)0; + uint32_t vector = 0; + switch ((int)obj->uart) { + case UART_0: irq_n=UART0_RX_TX_IRQn; vector = (uint32_t)&uart0_irq; break; + case UART_1: irq_n=UART1_RX_TX_IRQn; vector = (uint32_t)&uart1_irq; break; + case UART_2: irq_n=UART2_RX_TX_IRQn; vector = (uint32_t)&uart2_irq; break; + } + + if (enable) { + switch (irq) { + case RxIrq: obj->uart->C2 |= (UART_C2_RIE_MASK); break; + case TxIrq: obj->uart->C2 |= (UART_C2_TIE_MASK); break; + } + NVIC_SetVector(irq_n, vector); + NVIC_EnableIRQ(irq_n); + + } else { // disable + int all_disabled = 0; + SerialIrq other_irq = (irq == RxIrq) ? (TxIrq) : (RxIrq); + switch (irq) { + case RxIrq: obj->uart->C2 &= ~(UART_C2_RIE_MASK); break; + case TxIrq: obj->uart->C2 &= ~(UART_C2_TIE_MASK); break; + } + switch (other_irq) { + case RxIrq: all_disabled = (obj->uart->C2 & (UART_C2_RIE_MASK)) == 0; break; + case TxIrq: all_disabled = (obj->uart->C2 & (UART_C2_TIE_MASK)) == 0; break; + } + if (all_disabled) + NVIC_DisableIRQ(irq_n); + } +} + +/****************************************************************************** + * READ/WRITE + ******************************************************************************/ +int serial_getc(serial_t *obj) { + while (!serial_readable(obj)); + return obj->uart->D; +} + +void serial_putc(serial_t *obj, int c) { + while (!serial_writable(obj)); + obj->uart->D = c; +} + +int serial_readable(serial_t *obj) { + + return (obj->uart->S1 & UART_S1_RDRF_MASK); +} + +int serial_writable(serial_t *obj) { + + return (obj->uart->S1 & UART_S1_TDRE_MASK); +} + +void serial_clear(serial_t *obj) { +} + +void serial_pinout_tx(PinName tx) { + pinmap_pinout(tx, PinMap_UART_TX); +} + +void serial_break_set(serial_t *obj) { + obj->uart->C2 |= UART_C2_SBK_MASK; +} + +void serial_break_clear(serial_t *obj) { + obj->uart->C2 &= ~UART_C2_SBK_MASK; +} + diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/spi_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/spi_api.c new file mode 100644 index 0000000000..a8d0a2760c --- /dev/null +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/spi_api.c @@ -0,0 +1,200 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2013 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#include "spi_api.h" + +#include + +#include "cmsis.h" +#include "pinmap.h" +#include "error.h" + +static const PinMap PinMap_SPI_SCLK[] = { + {PTA15, SPI_0, 2}, + {PTB11, SPI_0, 2}, + {PTC5, SPI_0, 2}, + {PTD1, SPI_0, 2}, + {PTD5, SPI_0, 2}, + {PTE2, SPI_0, 2}, + {NC , NC , 0} +}; + +static const PinMap PinMap_SPI_MOSI[] = { + {PTA16, SPI_0, 2}, + {PTA17, SPI_0, 5}, + {PTB16, SPI_0, 2}, + {PTB17, SPI_0, 5}, + {PTC6, SPI_0, 2}, + {PTC7, SPI_0, 5}, + {PTD2, SPI_0, 2}, + {PTD3, SPI_0, 5}, + {PTD6, SPI_0, 2}, + {PTD7, SPI_0, 5}, + {PTE1, SPI_0, 2}, + {PTE3, SPI_0, 5}, + {NC , NC , 0} +}; + +static const PinMap PinMap_SPI_MISO[] = { + {PTA16, SPI_0, 5}, + {PTA17, SPI_0, 2}, + {PTB16, SPI_0, 5}, + {PTB17, SPI_0, 2}, + {PTC6, SPI_0, 5}, + {PTC7, SPI_0, 2}, + {PTD2, SPI_0, 5}, + {PTD3, SPI_0, 2}, + {PTD6, SPI_0, 5}, + {PTD7, SPI_0, 2}, + {PTE1, SPI_0, 5}, + {PTE3, SPI_0, 2}, + {NC , NC , 0} +}; + +static const PinMap PinMap_SPI_SSEL[] = { + {PTA14, SPI_0, 2}, + {PTB10, SPI_0, 2}, + {PTC4, SPI_0, 2}, + {PTD0, SPI_0, 2}, + {PTD4, SPI_0, 2}, + {PTE4, SPI_0, 2}, + {NC , NC , 0} +}; + +void spi_init(spi_t *obj, PinName mosi, PinName miso, PinName sclk, PinName ssel) { + // determine the SPI to use + SPIName spi_mosi = (SPIName)pinmap_peripheral(mosi, PinMap_SPI_MOSI); + SPIName spi_miso = (SPIName)pinmap_peripheral(miso, PinMap_SPI_MISO); + SPIName spi_sclk = (SPIName)pinmap_peripheral(sclk, PinMap_SPI_SCLK); + SPIName spi_ssel = (SPIName)pinmap_peripheral(ssel, PinMap_SPI_SSEL); + SPIName spi_data = (SPIName)pinmap_merge(spi_mosi, spi_miso); + SPIName spi_cntl = (SPIName)pinmap_merge(spi_sclk, spi_ssel); + + obj->spi = (SPI_Type*)pinmap_merge(spi_data, spi_cntl); + if ((int)obj->spi == NC) { + error("SPI pinout mapping failed"); + } + + // enable power and clocking + switch ((int)obj->spi) { + case SPI_0: SIM->SCGC5 |= 1 << 11; SIM->SCGC4 |= 1 << 22; break; + //case SPI_1: SIM->SCGC5 |= 1 << 13; SIM->SCGC4 |= 1 << 23; break; + } + + // set default format and frequency + if (ssel == NC) { + spi_format(obj, 8, 0, 0); // 8 bits, mode 0, master + } else { + spi_format(obj, 8, 0, 1); // 8 bits, mode 0, slave + } + spi_frequency(obj, 1000000); + + // enable SPI + obj->spi->MCR |= SPI_MCR_CONT_SCKE_MASK; + + // pin out the spi pins + pinmap_pinout(mosi, PinMap_SPI_MOSI); + pinmap_pinout(miso, PinMap_SPI_MISO); + pinmap_pinout(sclk, PinMap_SPI_SCLK); + if (ssel != NC) { + pinmap_pinout(ssel, PinMap_SPI_SSEL); + } +} + +void spi_free(spi_t *obj) { + // [TODO] +} +void spi_format(spi_t *obj, int bits, int mode, int slave) { + if (bits != 8) { + error("Only 8bits SPI supported"); + } + + if ((mode < 0) || (mode > 3)) { + error("SPI mode unsupported"); + } + + uint8_t polarity = (mode & 0x2) ? 1 : 0; + uint8_t phase = (mode & 0x1) ? 1 : 0; + uint8_t c1_data = ((!slave) << 4) | (polarity << 3) | (phase << 2); + + // clear MSTR, CPOL and CPHA bits + obj->spi->MCR &= ~SPI_MCR_MSTR_MASK; + + // write new value + obj->spi->MCR |= c1_data; +} + +void spi_frequency(spi_t *obj, int hz) { + // uint32_t error = 0; + // uint32_t p_error = 0xffffffff; + // uint32_t ref = 0; + // uint8_t spr = 0; + // uint8_t ref_spr = 0; + // uint8_t ref_prescaler = 0; + + // // bus clk + // uint32_t PCLK = 48000000u; + // uint8_t prescaler = 1; + // uint8_t divisor = 2; + + // for (prescaler = 1; prescaler <= 8; prescaler++) { + // divisor = 2; + // for (spr = 0; spr <= 8; spr++, divisor *= 2) { + // ref = PCLK / (prescaler*divisor); + // if (ref > (uint32_t)hz) + // continue; + // error = hz - ref; + // if (error < p_error) { + // ref_spr = spr; + // ref_prescaler = prescaler - 1; + // p_error = error; + // } + // } + // } + + // // set SPPR and SPR + // obj->spi->CTAR = ((ref_prescaler & 0x7) << 4) | (ref_spr & 0xf); +} + +static inline int spi_writeable(spi_t * obj) { + return 0;//(obj->spi->S & SPI_S_SPTEF_MASK) ? 1 : 0; +} + +static inline int spi_readable(spi_t * obj) { + return 0;//(obj->spi->S & SPI_S_SPRF_MASK) ? 1 : 0; +} + +int spi_master_write(spi_t *obj, int value) { + // wait tx buffer empty + // while(!spi_writeable(obj)); + // obj->spi->D = (value & 0xff); + + // // wait rx buffer full + // while (!spi_readable(obj)); + return 0;//obj->spi->D & 0xff; +} + +int spi_slave_receive(spi_t *obj) { + return 0;//spi_readable(obj); +} + +int spi_slave_read(spi_t *obj) { + return 0;//obj->spi->D; +} + +void spi_slave_write(spi_t *obj, int value) { + // while (!spi_writeable(obj)); + // obj->spi->D = value; +} diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/us_ticker.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/us_ticker.c new file mode 100644 index 0000000000..964967ea6f --- /dev/null +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/us_ticker.c @@ -0,0 +1,146 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2013 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ +#include +#include "us_ticker_api.h" +#include "PeripheralNames.h" + +static void pit_init(void); +static void lptmr_init(void); + +static int us_ticker_inited = 0; + +void us_ticker_init(void) { + if (us_ticker_inited) return; + us_ticker_inited = 1; + + pit_init(); + lptmr_init(); +} + +/****************************************************************************** + * Timer for us timing. + ******************************************************************************/ +static void pit_init(void) { + SIM->SCGC6 |= SIM_SCGC6_PIT_MASK; // Clock PIT + PIT->MCR = 0; // Enable PIT + + // Channel 1 + PIT->CHANNEL[1].LDVAL = 0xFFFFFFFF; + PIT->CHANNEL[1].TCTRL = PIT_TCTRL_TIE_MASK; // Chain to timer 0, disable Interrupts + PIT->CHANNEL[1].TCTRL |= PIT_TCTRL_TEN_MASK; // Start timer 1 + + // Use channel 0 as a prescaler for channel 1 + PIT->CHANNEL[0].LDVAL = 23; + PIT->CHANNEL[0].TCTRL = PIT_TCTRL_TEN_MASK; // Start timer 0, disable interrupts +} + +uint32_t us_ticker_read() { + if (!us_ticker_inited) + us_ticker_init(); + + // The PIT is a countdown timer + return ~(PIT->CHANNEL[1].CVAL); +} + +/****************************************************************************** + * Timer Event + * + * It schedules interrupts at given (32bit)us interval of time. + * It is implemented used the 16bit Low Power Timer that remains powered in all + * power modes. + ******************************************************************************/ +static void lptmr_isr(void); + +static void lptmr_init(void) { + /* Clock the timer */ + SIM->SCGC5 |= SIM_SCGC5_LPTIMER_MASK; + + /* Reset */ + LPTMR0->CSR = 0; + + /* Set interrupt handler */ + NVIC_SetVector(LPTimer_IRQn, (uint32_t)lptmr_isr); + NVIC_EnableIRQ(LPTimer_IRQn); + + /* Clock at (1)MHz -> (1)tick/us */ + LPTMR0->PSR = LPTMR_PSR_PCS(3); // OSCERCLK -> 8MHz + LPTMR0->PSR |= LPTMR_PSR_PRESCALE(2); // divide by 8 +} + +void us_ticker_disable_interrupt(void) { + LPTMR0->CSR &= ~LPTMR_CSR_TIE_MASK; +} + +void us_ticker_clear_interrupt(void) { + // we already clear interrupt in lptmr_isr +} + +static uint32_t us_ticker_int_counter = 0; +static uint16_t us_ticker_int_remainder = 0; + +static void lptmr_set(unsigned short count) { + /* Reset */ + LPTMR0->CSR = 0; + + /* Set the compare register */ + LPTMR0->CMR = count; + + /* Enable interrupt */ + LPTMR0->CSR |= LPTMR_CSR_TIE_MASK; + + /* Start the timer */ + LPTMR0->CSR |= LPTMR_CSR_TEN_MASK; +} + +static void lptmr_isr(void) { + // write 1 to TCF to clear the LPT timer compare flag + LPTMR0->CSR |= LPTMR_CSR_TCF_MASK; + + if (us_ticker_int_counter > 0) { + lptmr_set(0xFFFF); + us_ticker_int_counter--; + + } else { + if (us_ticker_int_remainder > 0) { + lptmr_set(us_ticker_int_remainder); + us_ticker_int_remainder = 0; + + } else { + // This function is going to disable the interrupts if there are + // no other events in the queue + us_ticker_irq_handler(); + } + } +} + +void us_ticker_set_interrupt(unsigned int timestamp) { + int delta = (int)(timestamp - us_ticker_read()); + if (delta <= 0) { + // This event was in the past: + us_ticker_irq_handler(); + return; + } + + us_ticker_int_counter = (uint32_t)(delta >> 16); + us_ticker_int_remainder = (uint16_t)(0xFFFF & delta); + if (us_ticker_int_counter > 0) { + lptmr_set(0xFFFF); + us_ticker_int_counter--; + } else { + lptmr_set(us_ticker_int_remainder); + us_ticker_int_remainder = 0; + } +} diff --git a/workspace_tools/targets.py b/workspace_tools/targets.py index b22c237a18..46b2cece02 100644 --- a/workspace_tools/targets.py +++ b/workspace_tools/targets.py @@ -132,6 +132,18 @@ class KL46Z(Target): self.is_disk_virtual = True +class K20D5M(Target): + def __init__(self): + Target.__init__(self) + + self.core = "Cortex-M4" + + self.extra_labels = ['Freescale'] + + self.supported_toolchains = ["GCC_ARM"] + + self.is_disk_virtual = True + class LPC812(Target): def __init__(self): @@ -312,6 +324,7 @@ TARGETS = [ KL05Z(), KL25Z(), KL46Z(), + K20D5M(), LPC812(), LPC810(), LPC4088(), From 4e09b52a71f4dc6c54799939af8cba6d84dae407 Mon Sep 17 00:00:00 2001 From: 0xc0170 Date: Tue, 19 Nov 2013 20:06:26 +0100 Subject: [PATCH 02/33] K20 uVision files, ld NVIC offset - K20 KEIL files - clock set to 1 (48MHz) - offset in GCC ld for vectors in RAM - us ticker - PIT timer interrupt implementation --- .../TOOLCHAIN_ARM_STD/MK20D5.sct | 14 + .../TOOLCHAIN_ARM_STD/startup_MK20D5.s | 654 ++++++++++++++++++ .../TARGET_K20D5M/TOOLCHAIN_ARM_STD/sys.cpp | 31 + .../TARGET_K20D5M/TOOLCHAIN_GCC_ARM/MK20D5.ld | 4 +- .../TOOLCHAIN_GCC_ARM/startup_MK20D5.s | 11 + .../TARGET_K20D5M/system_MK20D5.c | 2 +- .../TARGET_K20D5M/us_ticker.c | 33 +- workspace_tools/targets.py | 2 +- 8 files changed, 733 insertions(+), 18 deletions(-) create mode 100644 libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/MK20D5.sct create mode 100644 libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/startup_MK20D5.s create mode 100644 libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/sys.cpp diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/MK20D5.sct b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/MK20D5.sct new file mode 100644 index 0000000000..96520733dc --- /dev/null +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/MK20D5.sct @@ -0,0 +1,14 @@ + +LR_IROM1 0x00000000 0x20000 { ; load region size_region (132k) + ER_IROM1 0x00000000 0x20000 { ; load address = execution address + *.o (RESET, +First) + *(InRoot$$Sections) + .ANY (+RO) + } + ; 8_byte_aligned(61 vect * 4 bytes) = 8_byte_aligned(0xF4) = 0xF8 + ; 0x4000 - 0xF8 = 0x3F08 + RW_IRAM1 0x1FFFE0F8 0x3F08 { + .ANY (+RW +ZI) + } +} + diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/startup_MK20D5.s b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/startup_MK20D5.s new file mode 100644 index 0000000000..f13c87d193 --- /dev/null +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/startup_MK20D5.s @@ -0,0 +1,654 @@ +;/***************************************************************************** +; * @file: startup_MK20D5.s +; * @purpose: CMSIS Cortex-M4 Core Device Startup File for the +; * MK20D5 +; * @version: 1.0 +; * @date: 2011-12-15 +; * +; * Copyright: 1997 - 2012 Freescale Semiconductor, Inc. All Rights Reserved. +;* +; *------- <<< Use Configuration Wizard in Context Menu >>> ------------------ +; * +; *****************************************************************************/ + + +; Stack Configuration +; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Stack_Size EQU 0x00000400 + + AREA STACK, NOINIT, READWRITE, ALIGN=3 +Stack_Mem SPACE Stack_Size +__initial_sp + + +; Heap Configuration +; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> +; + +Heap_Size EQU 0x00000000 + + AREA HEAP, NOINIT, READWRITE, ALIGN=3 +__heap_base +Heap_Mem SPACE Heap_Size +__heap_limit + + + PRESERVE8 + THUMB + + +; Vector Table Mapped to Address 0 at Reset + + AREA RESET, DATA, READONLY + EXPORT __Vectors + EXPORT __Vectors_End + EXPORT __Vectors_Size + +__Vectors DCD __initial_sp ; Top of Stack + DCD Reset_Handler ; Reset Handler + DCD NMI_Handler ; NMI Handler + DCD HardFault_Handler ; Hard Fault Handler + DCD MemManage_Handler ; MPU Fault Handler + DCD BusFault_Handler ; Bus Fault Handler + DCD UsageFault_Handler ; Usage Fault Handler + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD 0 ; Reserved + DCD SVC_Handler ; SVCall Handler + DCD DebugMon_Handler ; Debug Monitor Handler + DCD 0 ; Reserved + DCD PendSV_Handler ; PendSV Handler + DCD SysTick_Handler ; SysTick Handler + + ; External Interrupts + DCD DMA0_IRQHandler ; DMA channel 0 transfer complete interrupt + DCD DMA1_IRQHandler ; DMA channel 1 transfer complete interrupt + DCD DMA2_IRQHandler ; DMA channel 2 transfer complete interrupt + DCD DMA3_IRQHandler ; DMA channel 3 transfer complete interrupt + DCD DMA_Error_IRQHandler ; DMA error interrupt + DCD Reserved21_IRQHandler ; Reserved interrupt 21 + DCD FTFL_IRQHandler ; FTFL interrupt + DCD Read_Collision_IRQHandler ; Read collision interrupt + DCD LVD_LVW_IRQHandler ; Low Voltage Detect, Low Voltage Warning + DCD LLW_IRQHandler ; Low Leakage Wakeup + DCD Watchdog_IRQHandler ; WDOG interrupt + DCD I2C0_IRQHandler ; I2C0 interrupt + DCD SPI0_IRQHandler ; SPI0 interrupt + DCD I2S0_Tx_IRQHandler ; I2S0 transmit interrupt + DCD I2S0_Rx_IRQHandler ; I2S0 receive interrupt + DCD UART0_LON_IRQHandler ; UART0 LON interrupt + DCD UART0_RX_TX_IRQHandler ; UART0 receive/transmit interrupt + DCD UART0_ERR_IRQHandler ; UART0 error interrupt + DCD UART1_RX_TX_IRQHandler ; UART1 receive/transmit interrupt + DCD UART1_ERR_IRQHandler ; UART1 error interrupt + DCD UART2_RX_TX_IRQHandler ; UART2 receive/transmit interrupt + DCD UART2_ERR_IRQHandler ; UART2 error interrupt + DCD ADC0_IRQHandler ; ADC0 interrupt + DCD CMP0_IRQHandler ; CMP0 interrupt + DCD CMP1_IRQHandler ; CMP1 interrupt + DCD FTM0_IRQHandler ; FTM0 fault, overflow and channels interrupt + DCD FTM1_IRQHandler ; FTM1 fault, overflow and channels interrupt + DCD CMT_IRQHandler ; CMT interrupt + DCD RTC_IRQHandler ; RTC interrupt + DCD RTC_Seconds_IRQHandler ; RTC seconds interrupt + DCD PIT0_IRQHandler ; PIT timer channel 0 interrupt + DCD PIT1_IRQHandler ; PIT timer channel 1 interrupt + DCD PIT2_IRQHandler ; PIT timer channel 2 interrupt + DCD PIT3_IRQHandler ; PIT timer channel 3 interrupt + DCD PDB0_IRQHandler ; PDB0 interrupt + DCD USB0_IRQHandler ; USB0 interrupt + DCD USBDCD_IRQHandler ; USBDCD interrupt + DCD TSI0_IRQHandler ; TSI0 interrupt + DCD MCG_IRQHandler ; MCG interrupt + DCD LPTimer_IRQHandler ; LPTimer interrupt + DCD PORTA_IRQHandler ; Port A interrupt + DCD PORTB_IRQHandler ; Port B interrupt + DCD PORTC_IRQHandler ; Port C interrupt + DCD PORTD_IRQHandler ; Port D interrupt + DCD PORTE_IRQHandler ; Port E interrupt + DCD SWI_IRQHandler ; Software interrupt + DCD DefaultISR ; 62 + DCD DefaultISR ; 63 + DCD DefaultISR ; 64 + DCD DefaultISR ; 65 + DCD DefaultISR ; 66 + DCD DefaultISR ; 67 + DCD DefaultISR ; 68 + DCD DefaultISR ; 69 + DCD DefaultISR ; 70 + DCD DefaultISR ; 71 + DCD DefaultISR ; 72 + DCD DefaultISR ; 73 + DCD DefaultISR ; 74 + DCD DefaultISR ; 75 + DCD DefaultISR ; 76 + DCD DefaultISR ; 77 + DCD DefaultISR ; 78 + DCD DefaultISR ; 79 + DCD DefaultISR ; 80 + DCD DefaultISR ; 81 + DCD DefaultISR ; 82 + DCD DefaultISR ; 83 + DCD DefaultISR ; 84 + DCD DefaultISR ; 85 + DCD DefaultISR ; 86 + DCD DefaultISR ; 87 + DCD DefaultISR ; 88 + DCD DefaultISR ; 89 + DCD DefaultISR ; 90 + DCD DefaultISR ; 91 + DCD DefaultISR ; 92 + DCD DefaultISR ; 93 + DCD DefaultISR ; 94 + DCD DefaultISR ; 95 + DCD DefaultISR ; 96 + DCD DefaultISR ; 97 + DCD DefaultISR ; 98 + DCD DefaultISR ; 99 + DCD DefaultISR ; 100 + DCD DefaultISR ; 101 + DCD DefaultISR ; 102 + DCD DefaultISR ; 103 + DCD DefaultISR ; 104 + DCD DefaultISR ; 105 + DCD DefaultISR ; 106 + DCD DefaultISR ; 107 + DCD DefaultISR ; 108 + DCD DefaultISR ; 109 + DCD DefaultISR ; 110 + DCD DefaultISR ; 111 + DCD DefaultISR ; 112 + DCD DefaultISR ; 113 + DCD DefaultISR ; 114 + DCD DefaultISR ; 115 + DCD DefaultISR ; 116 + DCD DefaultISR ; 117 + DCD DefaultISR ; 118 + DCD DefaultISR ; 119 + DCD DefaultISR ; 120 + DCD DefaultISR ; 121 + DCD DefaultISR ; 122 + DCD DefaultISR ; 123 + DCD DefaultISR ; 124 + DCD DefaultISR ; 125 + DCD DefaultISR ; 126 + DCD DefaultISR ; 127 + DCD DefaultISR ; 128 + DCD DefaultISR ; 129 + DCD DefaultISR ; 130 + DCD DefaultISR ; 131 + DCD DefaultISR ; 132 + DCD DefaultISR ; 133 + DCD DefaultISR ; 134 + DCD DefaultISR ; 135 + DCD DefaultISR ; 136 + DCD DefaultISR ; 137 + DCD DefaultISR ; 138 + DCD DefaultISR ; 139 + DCD DefaultISR ; 140 + DCD DefaultISR ; 141 + DCD DefaultISR ; 142 + DCD DefaultISR ; 143 + DCD DefaultISR ; 144 + DCD DefaultISR ; 145 + DCD DefaultISR ; 146 + DCD DefaultISR ; 147 + DCD DefaultISR ; 148 + DCD DefaultISR ; 149 + DCD DefaultISR ; 150 + DCD DefaultISR ; 151 + DCD DefaultISR ; 152 + DCD DefaultISR ; 153 + DCD DefaultISR ; 154 + DCD DefaultISR ; 155 + DCD DefaultISR ; 156 + DCD DefaultISR ; 157 + DCD DefaultISR ; 158 + DCD DefaultISR ; 159 + DCD DefaultISR ; 160 + DCD DefaultISR ; 161 + DCD DefaultISR ; 162 + DCD DefaultISR ; 163 + DCD DefaultISR ; 164 + DCD DefaultISR ; 165 + DCD DefaultISR ; 166 + DCD DefaultISR ; 167 + DCD DefaultISR ; 168 + DCD DefaultISR ; 169 + DCD DefaultISR ; 170 + DCD DefaultISR ; 171 + DCD DefaultISR ; 172 + DCD DefaultISR ; 173 + DCD DefaultISR ; 174 + DCD DefaultISR ; 175 + DCD DefaultISR ; 176 + DCD DefaultISR ; 177 + DCD DefaultISR ; 178 + DCD DefaultISR ; 179 + DCD DefaultISR ; 180 + DCD DefaultISR ; 181 + DCD DefaultISR ; 182 + DCD DefaultISR ; 183 + DCD DefaultISR ; 184 + DCD DefaultISR ; 185 + DCD DefaultISR ; 186 + DCD DefaultISR ; 187 + DCD DefaultISR ; 188 + DCD DefaultISR ; 189 + DCD DefaultISR ; 190 + DCD DefaultISR ; 191 + DCD DefaultISR ; 192 + DCD DefaultISR ; 193 + DCD DefaultISR ; 194 + DCD DefaultISR ; 195 + DCD DefaultISR ; 196 + DCD DefaultISR ; 197 + DCD DefaultISR ; 198 + DCD DefaultISR ; 199 + DCD DefaultISR ; 200 + DCD DefaultISR ; 201 + DCD DefaultISR ; 202 + DCD DefaultISR ; 203 + DCD DefaultISR ; 204 + DCD DefaultISR ; 205 + DCD DefaultISR ; 206 + DCD DefaultISR ; 207 + DCD DefaultISR ; 208 + DCD DefaultISR ; 209 + DCD DefaultISR ; 210 + DCD DefaultISR ; 211 + DCD DefaultISR ; 212 + DCD DefaultISR ; 213 + DCD DefaultISR ; 214 + DCD DefaultISR ; 215 + DCD DefaultISR ; 216 + DCD DefaultISR ; 217 + DCD DefaultISR ; 218 + DCD DefaultISR ; 219 + DCD DefaultISR ; 220 + DCD DefaultISR ; 221 + DCD DefaultISR ; 222 + DCD DefaultISR ; 223 + DCD DefaultISR ; 224 + DCD DefaultISR ; 225 + DCD DefaultISR ; 226 + DCD DefaultISR ; 227 + DCD DefaultISR ; 228 + DCD DefaultISR ; 229 + DCD DefaultISR ; 230 + DCD DefaultISR ; 231 + DCD DefaultISR ; 232 + DCD DefaultISR ; 233 + DCD DefaultISR ; 234 + DCD DefaultISR ; 235 + DCD DefaultISR ; 236 + DCD DefaultISR ; 237 + DCD DefaultISR ; 238 + DCD DefaultISR ; 239 + DCD DefaultISR ; 240 + DCD DefaultISR ; 241 + DCD DefaultISR ; 242 + DCD DefaultISR ; 243 + DCD DefaultISR ; 244 + DCD DefaultISR ; 245 + DCD DefaultISR ; 246 + DCD DefaultISR ; 247 + DCD DefaultISR ; 248 + DCD DefaultISR ; 249 + DCD DefaultISR ; 250 + DCD DefaultISR ; 251 + DCD DefaultISR ; 252 + DCD DefaultISR ; 253 + DCD DefaultISR ; 254 + DCD DefaultISR ; 255 +__Vectors_End + +__Vectors_Size EQU __Vectors_End - __Vectors + +; Flash Configuration +; 16-byte flash configuration field that stores default protection settings (loaded on reset) +; and security information that allows the MCU to restrict acces to the FTFL module. +; Backdoor Comparison Key +; Backdoor Key 0 <0x0-0xFF:2> +; Backdoor Key 1 <0x0-0xFF:2> +; Backdoor Key 2 <0x0-0xFF:2> +; Backdoor Key 3 <0x0-0xFF:2> +; Backdoor Key 4 <0x0-0xFF:2> +; Backdoor Key 5 <0x0-0xFF:2> +; Backdoor Key 6 <0x0-0xFF:2> +; Backdoor Key 7 <0x0-0xFF:2> +BackDoorK0 EQU 0xFF +BackDoorK1 EQU 0xFF +BackDoorK2 EQU 0xFF +BackDoorK3 EQU 0xFF +BackDoorK4 EQU 0xFF +BackDoorK5 EQU 0xFF +BackDoorK6 EQU 0xFF +BackDoorK7 EQU 0xFF +; +; Program flash protection bytes (FPROT) +; Each program flash region can be protected from program and erase operation by setting the associated PROT bit. +; Each bit protects a 1/32 region of the program flash memory. +; FPROT0 +; Program flash protection bytes +; 1/32 - 8/32 region +; FPROT0.0 +; FPROT0.1 +; FPROT0.2 +; FPROT0.3 +; FPROT0.4 +; FPROT0.5 +; FPROT0.6 +; FPROT0.7 +nFPROT0 EQU 0x00 +FPROT0 EQU nFPROT0:EOR:0xFF +; +; FPROT1 +; Program Flash Region Protect Register 1 +; 9/32 - 16/32 region +; FPROT1.0 +; FPROT1.1 +; FPROT1.2 +; FPROT1.3 +; FPROT1.4 +; FPROT1.5 +; FPROT1.6 +; FPROT1.7 +nFPROT1 EQU 0x00 +FPROT1 EQU nFPROT1:EOR:0xFF +; +; FPROT2 +; Program Flash Region Protect Register 2 +; 17/32 - 24/32 region +; FPROT2.0 +; FPROT2.1 +; FPROT2.2 +; FPROT2.3 +; FPROT2.4 +; FPROT2.5 +; FPROT2.6 +; FPROT2.7 +nFPROT2 EQU 0x00 +FPROT2 EQU nFPROT2:EOR:0xFF +; +; FPROT3 +; Program Flash Region Protect Register 3 +; 25/32 - 32/32 region +; FPROT3.0 +; FPROT3.1 +; FPROT3.2 +; FPROT3.3 +; FPROT3.4 +; FPROT3.5 +; FPROT3.6 +; FPROT3.7 +nFPROT3 EQU 0x00 +FPROT3 EQU nFPROT3:EOR:0xFF +; +; +; Data flash protection byte (FDPROT) +; Each bit protects a 1/8 region of the data flash memory. +; (Program flash only devices: Reserved) +; FDPROT.0 +; FDPROT.1 +; FDPROT.2 +; FDPROT.3 +; FDPROT.4 +; FDPROT.5 +; FDPROT.6 +; FDPROT.7 +nFDPROT EQU 0x00 +FDPROT EQU nFDPROT:EOR:0xFF +; +; EEPROM protection byte (FEPROT) +; FlexNVM devices: Each bit protects a 1/8 region of the EEPROM. +; (Program flash only devices: Reserved) +; FEPROT.0 +; FEPROT.1 +; FEPROT.2 +; FEPROT.3 +; FEPROT.4 +; FEPROT.5 +; FEPROT.6 +; FEPROT.7 +nFEPROT EQU 0x00 +FEPROT EQU nFEPROT:EOR:0xFF +; +; Flash nonvolatile option byte (FOPT) +; Allows the user to customize the operation of the MCU at boot time. +; LPBOOT +; <0=> Low-power boot +; <1=> normal boot +; EZPORT_DIS +; <0=> EzPort operation is enabled +; <1=> EzPort operation is disabled +FOPT EQU 0xFF +; +; Flash security byte (FSEC) +; WARNING: If SEC field is configured as "MCU security status is secure" and MEEN field is configured as "Mass erase is disabled", +; MCU's security status cannot be set back to unsecure state since Mass erase via the debugger is blocked !!! +; SEC +; <2=> MCU security status is unsecure +; <3=> MCU security status is secure +; Flash Security +; This bits define the security state of the MCU. +; FSLACC +; <2=> Freescale factory access denied +; <3=> Freescale factory access granted +; Freescale Failure Analysis Access Code +; This bits define the security state of the MCU. +; MEEN +; <2=> Mass erase is disabled +; <3=> Mass erase is enabled +; Mass Erase Enable Bits +; Enables and disables mass erase capability of the FTFL module +; KEYEN +; <2=> Backdoor key access enabled +; <3=> Backdoor key access disabled +; Backdoor key Security Enable +; These bits enable and disable backdoor key access to the FTFL module. +FSEC EQU 0xFE +; +; + IF :LNOT::DEF:RAM_TARGET + AREA |.ARM.__at_0x400|, CODE, READONLY + DCB BackDoorK0, BackDoorK1, BackDoorK2, BackDoorK3 + DCB BackDoorK4, BackDoorK5, BackDoorK6, BackDoorK7 + DCB FPROT0, FPROT1, FPROT2, FPROT3 + DCB FSEC, FOPT, FEPROT, FDPROT + ENDIF + + AREA |.text|, CODE, READONLY + + +; Reset Handler + +Reset_Handler PROC + EXPORT Reset_Handler [WEAK] + IMPORT SystemInit + IMPORT __main + LDR R0, =SystemInit + BLX R0 + LDR R0, =__main + BX R0 + ENDP + + +; Dummy Exception Handlers (infinite loops which can be modified) + +NMI_Handler PROC + EXPORT NMI_Handler [WEAK] + B . + ENDP +HardFault_Handler\ + PROC + EXPORT HardFault_Handler [WEAK] + B . + ENDP +MemManage_Handler\ + PROC + EXPORT MemManage_Handler [WEAK] + B . + ENDP +BusFault_Handler\ + PROC + EXPORT BusFault_Handler [WEAK] + B . + ENDP +UsageFault_Handler\ + PROC + EXPORT UsageFault_Handler [WEAK] + B . + ENDP +SVC_Handler PROC + EXPORT SVC_Handler [WEAK] + B . + ENDP +DebugMon_Handler\ + PROC + EXPORT DebugMon_Handler [WEAK] + B . + ENDP +PendSV_Handler PROC + EXPORT PendSV_Handler [WEAK] + B . + ENDP +SysTick_Handler PROC + EXPORT SysTick_Handler [WEAK] + B . + ENDP + +Default_Handler PROC + EXPORT DMA0_IRQHandler [WEAK] + EXPORT DMA1_IRQHandler [WEAK] + EXPORT DMA2_IRQHandler [WEAK] + EXPORT DMA3_IRQHandler [WEAK] + EXPORT DMA_Error_IRQHandler [WEAK] + EXPORT Reserved21_IRQHandler [WEAK] + EXPORT FTFL_IRQHandler [WEAK] + EXPORT Read_Collision_IRQHandler [WEAK] + EXPORT LVD_LVW_IRQHandler [WEAK] + EXPORT LLW_IRQHandler [WEAK] + EXPORT Watchdog_IRQHandler [WEAK] + EXPORT I2C0_IRQHandler [WEAK] + EXPORT SPI0_IRQHandler [WEAK] + EXPORT I2S0_Tx_IRQHandler [WEAK] + EXPORT I2S0_Rx_IRQHandler [WEAK] + EXPORT UART0_LON_IRQHandler [WEAK] + EXPORT UART0_RX_TX_IRQHandler [WEAK] + EXPORT UART0_ERR_IRQHandler [WEAK] + EXPORT UART1_RX_TX_IRQHandler [WEAK] + EXPORT UART1_ERR_IRQHandler [WEAK] + EXPORT UART2_RX_TX_IRQHandler [WEAK] + EXPORT UART2_ERR_IRQHandler [WEAK] + EXPORT ADC0_IRQHandler [WEAK] + EXPORT CMP0_IRQHandler [WEAK] + EXPORT CMP1_IRQHandler [WEAK] + EXPORT FTM0_IRQHandler [WEAK] + EXPORT FTM1_IRQHandler [WEAK] + EXPORT CMT_IRQHandler [WEAK] + EXPORT RTC_IRQHandler [WEAK] + EXPORT RTC_Seconds_IRQHandler [WEAK] + EXPORT PIT0_IRQHandler [WEAK] + EXPORT PIT1_IRQHandler [WEAK] + EXPORT PIT2_IRQHandler [WEAK] + EXPORT PIT3_IRQHandler [WEAK] + EXPORT PDB0_IRQHandler [WEAK] + EXPORT USB0_IRQHandler [WEAK] + EXPORT USBDCD_IRQHandler [WEAK] + EXPORT TSI0_IRQHandler [WEAK] + EXPORT MCG_IRQHandler [WEAK] + EXPORT LPTimer_IRQHandler [WEAK] + EXPORT PORTA_IRQHandler [WEAK] + EXPORT PORTB_IRQHandler [WEAK] + EXPORT PORTC_IRQHandler [WEAK] + EXPORT PORTD_IRQHandler [WEAK] + EXPORT PORTE_IRQHandler [WEAK] + EXPORT SWI_IRQHandler [WEAK] + EXPORT DefaultISR [WEAK] + +DMA0_IRQHandler +DMA1_IRQHandler +DMA2_IRQHandler +DMA3_IRQHandler +DMA_Error_IRQHandler +Reserved21_IRQHandler +FTFL_IRQHandler +Read_Collision_IRQHandler +LVD_LVW_IRQHandler +LLW_IRQHandler +Watchdog_IRQHandler +I2C0_IRQHandler +SPI0_IRQHandler +I2S0_Tx_IRQHandler +I2S0_Rx_IRQHandler +UART0_LON_IRQHandler +UART0_RX_TX_IRQHandler +UART0_ERR_IRQHandler +UART1_RX_TX_IRQHandler +UART1_ERR_IRQHandler +UART2_RX_TX_IRQHandler +UART2_ERR_IRQHandler +ADC0_IRQHandler +CMP0_IRQHandler +CMP1_IRQHandler +FTM0_IRQHandler +FTM1_IRQHandler +CMT_IRQHandler +RTC_IRQHandler +RTC_Seconds_IRQHandler +PIT0_IRQHandler +PIT1_IRQHandler +PIT2_IRQHandler +PIT3_IRQHandler +PDB0_IRQHandler +USB0_IRQHandler +USBDCD_IRQHandler +TSI0_IRQHandler +MCG_IRQHandler +LPTimer_IRQHandler +PORTA_IRQHandler +PORTB_IRQHandler +PORTC_IRQHandler +PORTD_IRQHandler +PORTE_IRQHandler +SWI_IRQHandler +DefaultISR + + B . + + ENDP + + + ALIGN + + +; User Initial Stack & Heap + + IF :DEF:__MICROLIB + + EXPORT __initial_sp + EXPORT __heap_base + EXPORT __heap_limit + + ELSE + + IMPORT __use_two_region_memory + EXPORT __user_initial_stackheap +__user_initial_stackheap + + LDR R0, = Heap_Mem + LDR R1, =(Stack_Mem + Stack_Size) + LDR R2, = (Heap_Mem + Heap_Size) + LDR R3, = Stack_Mem + BX LR + + ALIGN + + ENDIF + + + END diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/sys.cpp b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/sys.cpp new file mode 100644 index 0000000000..b129b2c2a5 --- /dev/null +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/sys.cpp @@ -0,0 +1,31 @@ +/* mbed Microcontroller Library - stackheap + * Copyright (C) 2009-2011 ARM Limited. All rights reserved. + * + * Setup a fixed single stack/heap memory model, + * between the top of the RW/ZI region and the stackpointer + */ + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include + +extern char Image$$RW_IRAM1$$ZI$$Limit[]; + +extern __value_in_regs struct __initial_stackheap __user_setup_stackheap(uint32_t R0, uint32_t R1, uint32_t R2, uint32_t R3) { + uint32_t zi_limit = (uint32_t)Image$$RW_IRAM1$$ZI$$Limit; + uint32_t sp_limit = __current_sp(); + + zi_limit = (zi_limit + 7) & ~0x7; // ensure zi_limit is 8-byte aligned + + struct __initial_stackheap r; + r.heap_base = zi_limit; + r.heap_limit = sp_limit; + return r; +} + +#ifdef __cplusplus +} +#endif diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/MK20D5.ld b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/MK20D5.ld index 8a9992365a..6d594af6f1 100644 --- a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/MK20D5.ld +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/MK20D5.ld @@ -1,5 +1,5 @@ /* - * KL25Z ARM GCC linker script file + * K20 ARM GCC linker script file */ MEMORY @@ -7,7 +7,7 @@ MEMORY VECTORS (rx) : ORIGIN = 0x00000000, LENGTH = 0x00000400 FLASH_PROTECTION (rx) : ORIGIN = 0x00000400, LENGTH = 0x00000010 FLASH (rx) : ORIGIN = 0x00000410, LENGTH = 128K - 0x00000410 - RAM (rwx) : ORIGIN = 0x1FFFE000, LENGTH = 16K + RAM (rwx) : ORIGIN = 0x1FFFE0F8, LENGTH = 16K - 0xC8 } /* Linker script to place sections and symbol values. Should be used together diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/startup_MK20D5.s b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/startup_MK20D5.s index 554be8349d..c91491787c 100644 --- a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/startup_MK20D5.s +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/startup_MK20D5.s @@ -211,4 +211,15 @@ Reset_Handler: def_irq_handler CPU_CLCD_IRQHandler def_irq_handler SPI_IRQHandler +/* 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/cmsis/TARGET_Freescale/TARGET_K20D5M/system_MK20D5.c b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/system_MK20D5.c index b78b71a707..393d1f0c5d 100644 --- a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/system_MK20D5.c +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/system_MK20D5.c @@ -44,7 +44,7 @@ #define DISABLE_WDOG 1 -#define CLOCK_SETUP 0 +#define CLOCK_SETUP 1 /* Predefined clock setups 0 ... Multipurpose Clock Generator (MCG) in FLL Engaged Internal (FEI) mode Reference clock source for MCG module is the slow internal clock source 32.768kHz diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/us_ticker.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/us_ticker.c index 964967ea6f..c58f9a06fc 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/us_ticker.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/us_ticker.c @@ -30,29 +30,34 @@ void us_ticker_init(void) { lptmr_init(); } +static uint32_t pit_us_ticker_counter = 0; + +void pit0_isr(void) { + pit_us_ticker_counter++; + PIT->CHANNEL[0].LDVAL = 48; // 1us + PIT->CHANNEL[0].TFLG = 1; +} + /****************************************************************************** * Timer for us timing. ******************************************************************************/ static void pit_init(void) { - SIM->SCGC6 |= SIM_SCGC6_PIT_MASK; // Clock PIT - PIT->MCR = 0; // Enable PIT - - // Channel 1 - PIT->CHANNEL[1].LDVAL = 0xFFFFFFFF; - PIT->CHANNEL[1].TCTRL = PIT_TCTRL_TIE_MASK; // Chain to timer 0, disable Interrupts - PIT->CHANNEL[1].TCTRL |= PIT_TCTRL_TEN_MASK; // Start timer 1 - - // Use channel 0 as a prescaler for channel 1 - PIT->CHANNEL[0].LDVAL = 23; - PIT->CHANNEL[0].TCTRL = PIT_TCTRL_TEN_MASK; // Start timer 0, disable interrupts + SIM->SCGC6 |= SIM_SCGC6_PIT_MASK; // Clock PIT + PIT->MCR = 0; // Enable PIT + + PIT->CHANNEL[0].LDVAL = 48; // 1us + PIT->CHANNEL[0].TCTRL |= PIT_TCTRL_TIE_MASK; + PIT->CHANNEL[0].TCTRL |= PIT_TCTRL_TEN_MASK; // Start timer 1 + + NVIC_SetVector(PIT0_IRQn, (uint32_t)pit0_isr); + NVIC_EnableIRQ(PIT0_IRQn); } uint32_t us_ticker_read() { if (!us_ticker_inited) us_ticker_init(); - - // The PIT is a countdown timer - return ~(PIT->CHANNEL[1].CVAL); + + return pit_us_ticker_counter; } /****************************************************************************** diff --git a/workspace_tools/targets.py b/workspace_tools/targets.py index 312d40d513..dfbae64354 100644 --- a/workspace_tools/targets.py +++ b/workspace_tools/targets.py @@ -140,7 +140,7 @@ class K20D5M(Target): self.extra_labels = ['Freescale'] - self.supported_toolchains = ["GCC_ARM"] + self.supported_toolchains = ["GCC_ARM", "ARM"] self.is_disk_virtual = True From 3dc97b20c023992070455de274617cb6e652774a Mon Sep 17 00:00:00 2001 From: 0xc0170 Date: Fri, 22 Nov 2013 21:21:01 +0100 Subject: [PATCH 03/33] startup ARM - stack pointer, serial functional - stack pointer correction - startup for ARM - clean up - GCC ARM linker - RAM size correction - NVIC - RAM address --- .../TOOLCHAIN_ARM_STD/startup_MK20D5.s | 244 +----------------- .../TARGET_K20D5M/TOOLCHAIN_GCC_ARM/MK20D5.ld | 2 +- .../TARGET_K20D5M/cmsis_nvic.c | 4 +- .../TARGET_Freescale/TARGET_K20D5M/PinNames.h | 4 +- .../TARGET_K20D5M/serial_api.c | 18 +- 5 files changed, 8 insertions(+), 264 deletions(-) diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/startup_MK20D5.s b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/startup_MK20D5.s index f13c87d193..db50cd5aa4 100644 --- a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/startup_MK20D5.s +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/startup_MK20D5.s @@ -12,28 +12,7 @@ ; *****************************************************************************/ -; Stack Configuration -; Stack Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Stack_Size EQU 0x00000400 - - AREA STACK, NOINIT, READWRITE, ALIGN=3 -Stack_Mem SPACE Stack_Size -__initial_sp - - -; Heap Configuration -; Heap Size (in Bytes) <0x0-0xFFFFFFFF:8> -; - -Heap_Size EQU 0x00000000 - - AREA HEAP, NOINIT, READWRITE, ALIGN=3 -__heap_base -Heap_Mem SPACE Heap_Size -__heap_limit - +__initial_sp EQU 0x20002000 ; Top of RAM PRESERVE8 THUMB @@ -110,200 +89,6 @@ __Vectors DCD __initial_sp ; Top of Stack DCD PORTD_IRQHandler ; Port D interrupt DCD PORTE_IRQHandler ; Port E interrupt DCD SWI_IRQHandler ; Software interrupt - DCD DefaultISR ; 62 - DCD DefaultISR ; 63 - DCD DefaultISR ; 64 - DCD DefaultISR ; 65 - DCD DefaultISR ; 66 - DCD DefaultISR ; 67 - DCD DefaultISR ; 68 - DCD DefaultISR ; 69 - DCD DefaultISR ; 70 - DCD DefaultISR ; 71 - DCD DefaultISR ; 72 - DCD DefaultISR ; 73 - DCD DefaultISR ; 74 - DCD DefaultISR ; 75 - DCD DefaultISR ; 76 - DCD DefaultISR ; 77 - DCD DefaultISR ; 78 - DCD DefaultISR ; 79 - DCD DefaultISR ; 80 - DCD DefaultISR ; 81 - DCD DefaultISR ; 82 - DCD DefaultISR ; 83 - DCD DefaultISR ; 84 - DCD DefaultISR ; 85 - DCD DefaultISR ; 86 - DCD DefaultISR ; 87 - DCD DefaultISR ; 88 - DCD DefaultISR ; 89 - DCD DefaultISR ; 90 - DCD DefaultISR ; 91 - DCD DefaultISR ; 92 - DCD DefaultISR ; 93 - DCD DefaultISR ; 94 - DCD DefaultISR ; 95 - DCD DefaultISR ; 96 - DCD DefaultISR ; 97 - DCD DefaultISR ; 98 - DCD DefaultISR ; 99 - DCD DefaultISR ; 100 - DCD DefaultISR ; 101 - DCD DefaultISR ; 102 - DCD DefaultISR ; 103 - DCD DefaultISR ; 104 - DCD DefaultISR ; 105 - DCD DefaultISR ; 106 - DCD DefaultISR ; 107 - DCD DefaultISR ; 108 - DCD DefaultISR ; 109 - DCD DefaultISR ; 110 - DCD DefaultISR ; 111 - DCD DefaultISR ; 112 - DCD DefaultISR ; 113 - DCD DefaultISR ; 114 - DCD DefaultISR ; 115 - DCD DefaultISR ; 116 - DCD DefaultISR ; 117 - DCD DefaultISR ; 118 - DCD DefaultISR ; 119 - DCD DefaultISR ; 120 - DCD DefaultISR ; 121 - DCD DefaultISR ; 122 - DCD DefaultISR ; 123 - DCD DefaultISR ; 124 - DCD DefaultISR ; 125 - DCD DefaultISR ; 126 - DCD DefaultISR ; 127 - DCD DefaultISR ; 128 - DCD DefaultISR ; 129 - DCD DefaultISR ; 130 - DCD DefaultISR ; 131 - DCD DefaultISR ; 132 - DCD DefaultISR ; 133 - DCD DefaultISR ; 134 - DCD DefaultISR ; 135 - DCD DefaultISR ; 136 - DCD DefaultISR ; 137 - DCD DefaultISR ; 138 - DCD DefaultISR ; 139 - DCD DefaultISR ; 140 - DCD DefaultISR ; 141 - DCD DefaultISR ; 142 - DCD DefaultISR ; 143 - DCD DefaultISR ; 144 - DCD DefaultISR ; 145 - DCD DefaultISR ; 146 - DCD DefaultISR ; 147 - DCD DefaultISR ; 148 - DCD DefaultISR ; 149 - DCD DefaultISR ; 150 - DCD DefaultISR ; 151 - DCD DefaultISR ; 152 - DCD DefaultISR ; 153 - DCD DefaultISR ; 154 - DCD DefaultISR ; 155 - DCD DefaultISR ; 156 - DCD DefaultISR ; 157 - DCD DefaultISR ; 158 - DCD DefaultISR ; 159 - DCD DefaultISR ; 160 - DCD DefaultISR ; 161 - DCD DefaultISR ; 162 - DCD DefaultISR ; 163 - DCD DefaultISR ; 164 - DCD DefaultISR ; 165 - DCD DefaultISR ; 166 - DCD DefaultISR ; 167 - DCD DefaultISR ; 168 - DCD DefaultISR ; 169 - DCD DefaultISR ; 170 - DCD DefaultISR ; 171 - DCD DefaultISR ; 172 - DCD DefaultISR ; 173 - DCD DefaultISR ; 174 - DCD DefaultISR ; 175 - DCD DefaultISR ; 176 - DCD DefaultISR ; 177 - DCD DefaultISR ; 178 - DCD DefaultISR ; 179 - DCD DefaultISR ; 180 - DCD DefaultISR ; 181 - DCD DefaultISR ; 182 - DCD DefaultISR ; 183 - DCD DefaultISR ; 184 - DCD DefaultISR ; 185 - DCD DefaultISR ; 186 - DCD DefaultISR ; 187 - DCD DefaultISR ; 188 - DCD DefaultISR ; 189 - DCD DefaultISR ; 190 - DCD DefaultISR ; 191 - DCD DefaultISR ; 192 - DCD DefaultISR ; 193 - DCD DefaultISR ; 194 - DCD DefaultISR ; 195 - DCD DefaultISR ; 196 - DCD DefaultISR ; 197 - DCD DefaultISR ; 198 - DCD DefaultISR ; 199 - DCD DefaultISR ; 200 - DCD DefaultISR ; 201 - DCD DefaultISR ; 202 - DCD DefaultISR ; 203 - DCD DefaultISR ; 204 - DCD DefaultISR ; 205 - DCD DefaultISR ; 206 - DCD DefaultISR ; 207 - DCD DefaultISR ; 208 - DCD DefaultISR ; 209 - DCD DefaultISR ; 210 - DCD DefaultISR ; 211 - DCD DefaultISR ; 212 - DCD DefaultISR ; 213 - DCD DefaultISR ; 214 - DCD DefaultISR ; 215 - DCD DefaultISR ; 216 - DCD DefaultISR ; 217 - DCD DefaultISR ; 218 - DCD DefaultISR ; 219 - DCD DefaultISR ; 220 - DCD DefaultISR ; 221 - DCD DefaultISR ; 222 - DCD DefaultISR ; 223 - DCD DefaultISR ; 224 - DCD DefaultISR ; 225 - DCD DefaultISR ; 226 - DCD DefaultISR ; 227 - DCD DefaultISR ; 228 - DCD DefaultISR ; 229 - DCD DefaultISR ; 230 - DCD DefaultISR ; 231 - DCD DefaultISR ; 232 - DCD DefaultISR ; 233 - DCD DefaultISR ; 234 - DCD DefaultISR ; 235 - DCD DefaultISR ; 236 - DCD DefaultISR ; 237 - DCD DefaultISR ; 238 - DCD DefaultISR ; 239 - DCD DefaultISR ; 240 - DCD DefaultISR ; 241 - DCD DefaultISR ; 242 - DCD DefaultISR ; 243 - DCD DefaultISR ; 244 - DCD DefaultISR ; 245 - DCD DefaultISR ; 246 - DCD DefaultISR ; 247 - DCD DefaultISR ; 248 - DCD DefaultISR ; 249 - DCD DefaultISR ; 250 - DCD DefaultISR ; 251 - DCD DefaultISR ; 252 - DCD DefaultISR ; 253 - DCD DefaultISR ; 254 - DCD DefaultISR ; 255 __Vectors_End __Vectors_Size EQU __Vectors_End - __Vectors @@ -624,31 +409,4 @@ DefaultISR ALIGN - - -; User Initial Stack & Heap - - IF :DEF:__MICROLIB - - EXPORT __initial_sp - EXPORT __heap_base - EXPORT __heap_limit - - ELSE - - IMPORT __use_two_region_memory - EXPORT __user_initial_stackheap -__user_initial_stackheap - - LDR R0, = Heap_Mem - LDR R1, =(Stack_Mem + Stack_Size) - LDR R2, = (Heap_Mem + Heap_Size) - LDR R3, = Stack_Mem - BX LR - - ALIGN - - ENDIF - - END diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/MK20D5.ld b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/MK20D5.ld index 6d594af6f1..600751ca06 100644 --- a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/MK20D5.ld +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/MK20D5.ld @@ -7,7 +7,7 @@ MEMORY VECTORS (rx) : ORIGIN = 0x00000000, LENGTH = 0x00000400 FLASH_PROTECTION (rx) : ORIGIN = 0x00000400, LENGTH = 0x00000010 FLASH (rx) : ORIGIN = 0x00000410, LENGTH = 128K - 0x00000410 - RAM (rwx) : ORIGIN = 0x1FFFE0F8, LENGTH = 16K - 0xC8 + RAM (rwx) : ORIGIN = 0x1FFFE0F8, LENGTH = 16K - 0xF8 } /* Linker script to place sections and symbol values. Should be used together diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis_nvic.c b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis_nvic.c index a15284bf92..8d64306859 100644 --- a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis_nvic.c +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis_nvic.c @@ -2,10 +2,10 @@ * Copyright (c) 2011 ARM Limited. All rights reserved. * * CMSIS-style functionality to support dynamic vectors - */ + */ #include "cmsis_nvic.h" -#define NVIC_RAM_VECTOR_ADDRESS (0x1FFFF000) // Vectors positioned at start of RAM +#define NVIC_RAM_VECTOR_ADDRESS (0x1FFFE000) // Vectors positioned at start of RAM #define NVIC_FLASH_VECTOR_ADDRESS (0x0) // Initial vector position in flash void NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) { diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PinNames.h b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PinNames.h index 051b63a7c6..9e0eec895d 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PinNames.h +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PinNames.h @@ -203,8 +203,8 @@ typedef enum { LED4 = LED_RED, // USB Pins - USBTX = PTB1, - USBRX = PTB2, + USBTX = PTB17, + USBRX = PTB16, // Arduino Headers D0 = PTE1, diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/serial_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/serial_api.c index d72c6ace91..6340f685e6 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/serial_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/serial_api.c @@ -28,26 +28,12 @@ * INITIALIZATION ******************************************************************************/ static const PinMap PinMap_UART_TX[] = { - {PTC4, UART_1, 3}, - {PTA2, UART_0, 2}, - {PTD5, UART_2, 3}, - {PTD3, UART_2, 3}, - {PTD7, UART_0, 3}, - {PTE20, UART_0, 4}, - {PTE22, UART_2, 4}, - {PTE0, UART_1, 3}, + {PTB17, UART_0, 3}, {NC , NC , 0} }; static const PinMap PinMap_UART_RX[] = { - {PTC3, UART_1, 3}, - {PTA1, UART_0, 2}, - {PTD4, UART_2, 3}, - {PTD2, UART_2, 3}, - {PTD6, UART_0, 3}, - {PTE23, UART_2, 4}, - {PTE21, UART_0, 4}, - {PTE1, UART_1, 3}, + {PTB16, UART_0, 3}, {NC , NC , 0} }; From 0e99a7c9bd712b2576e43254305b04bbf97986f2 Mon Sep 17 00:00:00 2001 From: 0xc0170 Date: Tue, 26 Nov 2013 20:08:13 +0100 Subject: [PATCH 04/33] Analog API - pins, analog pins (arduino) correction, irq - ADC - pins, mux - analog pins - Ax - irq - port A - E --- .../TARGET_K20D5M/PeripheralNames.h | 11 +---- .../TARGET_Freescale/TARGET_K20D5M/PinNames.h | 12 +++--- .../TARGET_K20D5M/analogin_api.c | 39 +++++++----------- .../TARGET_K20D5M/gpio_irq_api.c | 41 ++++++++++++------- 4 files changed, 48 insertions(+), 55 deletions(-) diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PeripheralNames.h b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PeripheralNames.h index ca406812e3..917e6fef08 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PeripheralNames.h +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PeripheralNames.h @@ -33,7 +33,6 @@ typedef enum { typedef enum { I2C_0 = (int)I2C0_BASE, - //I2C_1 = (int)I2C1_BASE, } I2CName; #define TPM_SHIFT 8 @@ -52,24 +51,17 @@ typedef enum { PWM_10 = (2 << TPM_SHIFT) | (1) // TPM2 CH1 } PWMName; -#define CHANNELS_A_SHIFT 5 typedef enum { - ADC0_SE0 = 0, - ADC0_SE3 = 3, - ADC0_SE4a = (1 << CHANNELS_A_SHIFT) | (4), ADC0_SE4b = 4, ADC0_SE5b = 5, ADC0_SE6b = 6, - ADC0_SE7a = (1 << CHANNELS_A_SHIFT) | (7), ADC0_SE7b = 7, ADC0_SE8 = 8, ADC0_SE9 = 9, - ADC0_SE11 = 11, ADC0_SE12 = 12, ADC0_SE13 = 13, ADC0_SE14 = 14, - ADC0_SE15 = 15, - ADC0_SE23 = 23 + ADC0_SE15 = 15 } ADCName; typedef enum { @@ -79,7 +71,6 @@ typedef enum { typedef enum { SPI_0 = (int)SPI0_BASE, - //SPI_1 = (int)SPI1_BASE, } SPIName; #ifdef __cplusplus diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PinNames.h b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PinNames.h index 9e0eec895d..fb9b164229 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PinNames.h +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PinNames.h @@ -224,12 +224,12 @@ typedef enum { D14 = PTB3, D15 = PTB2, - A0 = PTB0, - A1 = PTB1, - A2 = PTD5, - A3 = PTD6, - A4 = PTC1, - A5 = PTC0, + A0 = PTC0, + A1 = PTC1, + A2 = PTD6, + A3 = PTD5, + A4 = PTB1, + A5 = PTB0, // Not connected NC = (int)0xFFFFFFFF diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/analogin_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/analogin_api.c index 455fa835db..386384abcd 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/analogin_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/analogin_api.c @@ -20,23 +20,17 @@ #include "error.h" static const PinMap PinMap_ADC[] = { - {PTE20, ADC0_SE0, 0}, - {PTE22, ADC0_SE3, 0}, - {PTE21, ADC0_SE4a, 0}, - {PTE29, ADC0_SE4b, 0}, - {PTE30, ADC0_SE23, 0}, - {PTE23, ADC0_SE7a, 0}, - {PTB0, ADC0_SE8, 0}, - {PTB1, ADC0_SE9, 0}, - {PTB2, ADC0_SE12, 0}, - {PTB3, ADC0_SE13, 0}, - {PTC0, ADC0_SE14, 0}, - {PTC1, ADC0_SE15, 0}, - {PTC2, ADC0_SE11, 0}, - {PTD1, ADC0_SE5b, 0}, - {PTD5, ADC0_SE6b, 0}, - {PTD6, ADC0_SE7b, 0}, - {NC, NC, 0} + {PTC2, ADC0_SE4b, 0}, + {PTD1, ADC0_SE5b, 0}, + {PTD5, ADC0_SE6b, 0}, + {PTD6, ADC0_SE7b, 0}, + {PTB0, ADC0_SE8, 0}, + {PTB1, ADC0_SE9, 0}, + {PTB2, ADC0_SE12, 0}, + {PTB3, ADC0_SE13, 0}, + {PTC0, ADC0_SE14, 0}, + {PTC1, ADC0_SE15, 0}, + {NC, NC, 0} }; void analogin_init(analogin_t *obj, PinName pin) { @@ -50,12 +44,7 @@ void analogin_init(analogin_t *obj, PinName pin) { uint32_t port = (uint32_t)pin >> PORT_SHIFT; SIM->SCGC5 |= 1 << (SIM_SCGC5_PORTA_SHIFT + port); - uint32_t cfg2_muxsel = ADC_CFG2_MUXSEL_MASK; - if (obj->adc & (1 << CHANNELS_A_SHIFT)) { - cfg2_muxsel = 0; - } - - ADC0->SC1[1] = ADC_SC1_ADCH(obj->adc & ~(1 << CHANNELS_A_SHIFT)); + ADC0->SC1[1] = ADC_SC1_ADCH(obj->adc); ADC0->CFG1 = ADC_CFG1_ADLPC_MASK // Low-Power Configuration | ADC_CFG1_ADIV(3) // Clock Divide Select: (Input Clock)/8 @@ -63,7 +52,7 @@ void analogin_init(analogin_t *obj, PinName pin) { | ADC_CFG1_MODE(3) // (16)bits Resolution | ADC_CFG1_ADICLK(1); // Input Clock: (Bus Clock)/2 - ADC0->CFG2 = cfg2_muxsel // ADxxb or ADxxa channels + ADC0->CFG2 = ADC_CFG2_MUXSEL_MASK // ADxxb or ADxxa channels | ADC_CFG2_ADACKEN_MASK // Asynchronous Clock Output Enable | ADC_CFG2_ADHSC_MASK // High-Speed Configuration | ADC_CFG2_ADLSTS(0); // Long Sample Time Select @@ -78,7 +67,7 @@ void analogin_init(analogin_t *obj, PinName pin) { uint16_t analogin_read_u16(analogin_t *obj) { // start conversion - ADC0->SC1[0] = ADC_SC1_ADCH(obj->adc & ~(1 << CHANNELS_A_SHIFT)); + ADC0->SC1[0] = ADC_SC1_ADCH(obj->adc); // Wait Conversion Complete while ((ADC0->SC1[0] & ADC_SC1_COCO_MASK) != ADC_SC1_COCO_MASK); diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_irq_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_irq_api.c index a2aaf9c2d0..16245bbde4 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_irq_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_irq_api.c @@ -19,7 +19,7 @@ #include "gpio_irq_api.h" #include "error.h" -#define CHANNEL_NUM 64 +#define CHANNEL_NUM 160 static uint32_t channel_ids[CHANNEL_NUM] = {0}; static gpio_irq_handler irq_handler; @@ -39,8 +39,9 @@ static void handle_interrupt_in(PORT_Type *port, int ch_base) { uint32_t id = channel_ids[ch_base + i]; if (id == 0) continue; - GPIO_Type *gpio; + GPIO_Type *gpio = PTA; gpio_irq_event event = IRQ_NONE; + uint32_t port_num = (port - PORTA) >> 12; switch (port->PCR[i] & PORT_PCR_IRQC_MASK) { case IRQ_RAISING_EDGE: event = IRQ_RISE; @@ -51,7 +52,8 @@ static void handle_interrupt_in(PORT_Type *port, int ch_base) { break; case IRQ_EITHER_EDGE: - gpio = (port == PORTA) ? (PTA) : (PTD); + gpio += (port_num * 0x40); + //gpio = (port == PORTA) ? (PTA) : (PTD); event = (gpio->PDIR & pmask) ? (IRQ_RISE) : (IRQ_FALL); break; } @@ -63,7 +65,10 @@ static void handle_interrupt_in(PORT_Type *port, int ch_base) { } void gpio_irqA(void) {handle_interrupt_in(PORTA, 0);} -void gpio_irqD(void) {handle_interrupt_in(PORTD, 32);} +void gpio_irqB(void) {handle_interrupt_in(PORTB, 32);} +void gpio_irqC(void) {handle_interrupt_in(PORTC, 64);} +void gpio_irqD(void) {handle_interrupt_in(PORTD, 96);} +void gpio_irqE(void) {handle_interrupt_in(PORTE, 128);} int gpio_irq_init(gpio_irq_t *obj, PinName pin, gpio_irq_handler handler, uint32_t id) { if (pin == NC) return -1; @@ -76,17 +81,25 @@ int gpio_irq_init(gpio_irq_t *obj, PinName pin, gpio_irq_handler handler, uint32 uint32_t ch_base, vector; IRQn_Type irq_n; switch (obj->port) { - case PortA: - ch_base = 0; irq_n = PORTA_IRQn; vector = (uint32_t)gpio_irqA; - break; + case PortA: + ch_base = 0; irq_n = PORTA_IRQn; vector = (uint32_t)gpio_irqA; + break; + case PortB: + ch_base = 0; irq_n = PORTB_IRQn; vector = (uint32_t)gpio_irqB; + break; + case PortC: + ch_base = 0; irq_n = PORTC_IRQn; vector = (uint32_t)gpio_irqC; + break; + case PortD: + ch_base = 32; irq_n = PORTD_IRQn; vector = (uint32_t)gpio_irqD; + break; + case PortE: + ch_base = 0; irq_n = PORTE_IRQn; vector = (uint32_t)gpio_irqE; + break; - case PortD: - ch_base = 32; irq_n = PORTD_IRQn; vector = (uint32_t)gpio_irqD; - break; - - default: - error("gpio_irq only supported on port A and D\n"); - break; + default: + error("gpio_irq only supported on port A and D\n"); + break; } NVIC_SetVector(irq_n, vector); NVIC_EnableIRQ(irq_n); From c5a2e6ed0e9095cc8f1d4036ee75836edadd02c6 Mon Sep 17 00:00:00 2001 From: 0xc0170 Date: Wed, 27 Nov 2013 18:46:30 +0100 Subject: [PATCH 05/33] pwm, spi - pin definition, dac removed --- .../TARGET_K20D5M/PeripheralNames.h | 21 ++-- .../TARGET_Freescale/TARGET_K20D5M/device.h | 2 +- .../TARGET_Freescale/TARGET_K20D5M/objects.h | 4 - .../TARGET_Freescale/TARGET_K20D5M/port_api.c | 8 +- .../TARGET_K20D5M/pwmout_api.c | 46 ++------- .../TARGET_Freescale/TARGET_K20D5M/spi_api.c | 97 +++++++------------ 6 files changed, 59 insertions(+), 119 deletions(-) diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PeripheralNames.h b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PeripheralNames.h index 917e6fef08..d4b335b7e4 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PeripheralNames.h +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PeripheralNames.h @@ -37,18 +37,17 @@ typedef enum { #define TPM_SHIFT 8 typedef enum { - PWM_1 = (0 << TPM_SHIFT) | (0), // TPM0 CH0 - PWM_2 = (0 << TPM_SHIFT) | (1), // TPM0 CH1 - PWM_3 = (0 << TPM_SHIFT) | (2), // TPM0 CH2 - PWM_4 = (0 << TPM_SHIFT) | (3), // TPM0 CH3 - PWM_5 = (0 << TPM_SHIFT) | (4), // TPM0 CH4 - PWM_6 = (0 << TPM_SHIFT) | (5), // TPM0 CH5 + PWM_1 = (0 << TPM_SHIFT) | (0), // FTM0 CH0 + PWM_2 = (0 << TPM_SHIFT) | (1), // FTM0 CH1 + PWM_3 = (0 << TPM_SHIFT) | (2), // FTM0 CH2 + PWM_4 = (0 << TPM_SHIFT) | (3), // FTM0 CH3 + PWM_5 = (0 << TPM_SHIFT) | (4), // FTM0 CH4 + PWM_6 = (0 << TPM_SHIFT) | (5), // FTM0 CH5 + PWM_7 = (0 << TPM_SHIFT) | (6), // FTM0 CH6 + PWM_8 = (0 << TPM_SHIFT) | (7), // FTM0 CH7 - PWM_7 = (1 << TPM_SHIFT) | (0), // TPM1 CH0 - PWM_8 = (1 << TPM_SHIFT) | (1), // TPM1 CH1 - - PWM_9 = (2 << TPM_SHIFT) | (0), // TPM2 CH0 - PWM_10 = (2 << TPM_SHIFT) | (1) // TPM2 CH1 + PWM_9 = (1 << TPM_SHIFT) | (0), // FTM1 CH0 + PWM_10 = (1 << TPM_SHIFT) | (1), // FTM1 CH1 } PWMName; typedef enum { diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/device.h b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/device.h index 82374a0224..962e9ab2be 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/device.h +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/device.h @@ -23,7 +23,7 @@ #define DEVICE_INTERRUPTIN 1 #define DEVICE_ANALOGIN 1 -#define DEVICE_ANALOGOUT 1 +#define DEVICE_ANALOGOUT 0 #define DEVICE_SERIAL 1 diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/objects.h b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/objects.h index 30f428c187..257bc5c802 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/objects.h +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/objects.h @@ -54,10 +54,6 @@ struct analogin_s { ADCName adc; }; -struct dac_s { - DACName dac; -}; - struct i2c_s { I2C_Type *i2c; }; diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/port_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/port_api.c index 0598916da4..7a25a3b525 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/port_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/port_api.c @@ -54,8 +54,12 @@ void port_mode(port_t *obj, PinMode mode) { void port_dir(port_t *obj, PinDirection dir) { switch (dir) { - case PIN_INPUT : *obj->reg_dir &= ~obj->mask; break; - case PIN_OUTPUT: *obj->reg_dir |= obj->mask; break; + case PIN_INPUT : + *obj->reg_dir &= ~obj->mask; + break; + case PIN_OUTPUT: + *obj->reg_dir |= obj->mask; + break; } } diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pwmout_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pwmout_api.c index 1168fb9c67..438b33056c 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pwmout_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pwmout_api.c @@ -21,45 +21,16 @@ static const PinMap PinMap_PWM[] = { // LEDs - {LED_RED , PWM_9 , 3}, // PTB18, FTM2 CH0 - {LED_GREEN, PWM_10, 3}, // PTB19, FTM2 CH1 - {LED_BLUE , PWM_2 , 4}, // PTD1 , FTM0 CH1 + {LED_RED , PWM_3 , 3}, // PTC3, FTM0 CH2 + {LED_GREEN, PWM_5, 3}, // PTD4, FTM0 CH4 + {LED_BLUE , PWM_9 , 3}, // PTA2 , FTM0 CH7 // Arduino digital pinout - {D0, PWM_9 , 3}, // PTA1 , FTM2 CH0 - {D1, PWM_10, 3}, // PTA2 , FTM2 CH1 - {D2, PWM_5 , 4}, // PTD4 , FTM0 CH4 - {D3, PWM_7 , 3}, // PTA12, FTM1 CH0 - {D4, PWM_2 , 3}, // PTA4 , FTM0 CH1 - {D5, PWM_3 , 3}, // PTA5 , FTM0 CH2 - {D6, PWM_5 , 3}, // PTC8 , FTM0 CH4 - {D7, PWM_6 , 3}, // PTC9 , FTM0 CH5 - {D8, PWM_8 , 3}, // PTA13, FTM1 CH1 - {D9, PWM_6 , 4}, // PTD5 , FTM0 CH5 - {D10, PWM_1 , 4}, // PTD0 , FTM0 CH0 - {D11, PWM_3 , 4}, // PTD2 , FTM0 CH2 - {D12, PWM_4 , 4}, // PTD3 , FTM0 CH3 - {D13, PWM_2 , 4}, // PTD1 , FTM0 CH1, - - {PTA0, PWM_6, 3}, - {PTA3, PWM_1, 3}, - {PTB0, PWM_7, 3}, - {PTB1, PWM_8, 3}, - {PTB2, PWM_9, 3}, - {PTB3, PWM_10, 3}, - {PTC1, PWM_1, 4}, - {PTC2, PWM_2, 4}, - {PTC3, PWM_3, 4}, - {PTC4, PWM_4, 4}, - {PTE20, PWM_7, 3}, - {PTE21, PWM_8, 3}, - {PTE22, PWM_9, 3}, - {PTE23, PWM_10, 3}, - {PTE24, PWM_1, 3}, - {PTE25, PWM_2, 3}, - {PTE29, PWM_3, 3}, - {PTE30, PWM_4, 3}, - {PTE31, PWM_5, 3}, + {D3, PWM_5 , 3}, // PTA12, FTM0 CH4 + {D5, PWM_7 , 3}, // PTA1 , FTM0 CH6 + {D6, PWM_3 , 3}, // PTC3 , FTM0 CH2 + {D9, PWM_8 , 4}, // PTD2 , FTM0 CH7 + {D10, PWM_2 , 4}, // PTC2 , FTM0 CH1 {NC , NC , 0} }; @@ -78,7 +49,6 @@ void pwmout_init(pwmout_t* obj, PinName pin) { SIM->SCGC5 |= 1 << (SIM_SCGC5_PORTA_SHIFT + port); SIM->SCGC6 |= 1 << (SIM_SCGC6_FTM0_SHIFT + ftm_n); - SIM->SOPT2 |= SIM_SOPT2_CLKOUTSEL(1); // Clock source: MCGFLLCLK or MCGPLLCLK FTM_Type *ftm = (FTM_Type *)(FTM0_BASE + 0x1000 * ftm_n); ftm->SC = FTM_SC_CLKS(1) | FTM_SC_PS(6); // (48)MHz / 64 = (0.75)MHz diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/spi_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/spi_api.c index a8d0a2760c..65f2630dfd 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/spi_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/spi_api.c @@ -22,54 +22,26 @@ #include "error.h" static const PinMap PinMap_SPI_SCLK[] = { - {PTA15, SPI_0, 2}, - {PTB11, SPI_0, 2}, - {PTC5, SPI_0, 2}, - {PTD1, SPI_0, 2}, - {PTD5, SPI_0, 2}, - {PTE2, SPI_0, 2}, + {PTC5, SPI_0, 2}, + {PTD1, SPI_0, 2}, {NC , NC , 0} }; static const PinMap PinMap_SPI_MOSI[] = { - {PTA16, SPI_0, 2}, - {PTA17, SPI_0, 5}, - {PTB16, SPI_0, 2}, - {PTB17, SPI_0, 5}, - {PTC6, SPI_0, 2}, - {PTC7, SPI_0, 5}, - {PTD2, SPI_0, 2}, - {PTD3, SPI_0, 5}, - {PTD6, SPI_0, 2}, - {PTD7, SPI_0, 5}, - {PTE1, SPI_0, 2}, - {PTE3, SPI_0, 5}, + {PTD2, SPI_0, 2}, + {PTC6, SPI_0, 2}, {NC , NC , 0} }; static const PinMap PinMap_SPI_MISO[] = { - {PTA16, SPI_0, 5}, - {PTA17, SPI_0, 2}, - {PTB16, SPI_0, 5}, - {PTB17, SPI_0, 2}, - {PTC6, SPI_0, 5}, - {PTC7, SPI_0, 2}, - {PTD2, SPI_0, 5}, - {PTD3, SPI_0, 2}, - {PTD6, SPI_0, 5}, - {PTD7, SPI_0, 2}, - {PTE1, SPI_0, 5}, - {PTE3, SPI_0, 2}, + {PTD3, SPI_0, 2}, + {PTC7, SPI_0, 2}, {NC , NC , 0} }; static const PinMap PinMap_SPI_SSEL[] = { - {PTA14, SPI_0, 2}, - {PTB10, SPI_0, 2}, - {PTC4, SPI_0, 2}, - {PTD0, SPI_0, 2}, - {PTD4, SPI_0, 2}, - {PTE4, SPI_0, 2}, + {PTD0, SPI_0, 2}, + {PTC4, SPI_0, 2}, {NC , NC , 0} }; @@ -90,7 +62,6 @@ void spi_init(spi_t *obj, PinName mosi, PinName miso, PinName sclk, PinName ssel // enable power and clocking switch ((int)obj->spi) { case SPI_0: SIM->SCGC5 |= 1 << 11; SIM->SCGC4 |= 1 << 22; break; - //case SPI_1: SIM->SCGC5 |= 1 << 13; SIM->SCGC4 |= 1 << 23; break; } // set default format and frequency @@ -137,35 +108,35 @@ void spi_format(spi_t *obj, int bits, int mode, int slave) { } void spi_frequency(spi_t *obj, int hz) { - // uint32_t error = 0; - // uint32_t p_error = 0xffffffff; - // uint32_t ref = 0; - // uint8_t spr = 0; - // uint8_t ref_spr = 0; - // uint8_t ref_prescaler = 0; + uint32_t error = 0; + uint32_t p_error = 0xffffffff; + uint32_t ref = 0; + uint8_t spr = 0; + uint8_t ref_spr = 0; + uint8_t ref_prescaler = 0; - // // bus clk - // uint32_t PCLK = 48000000u; - // uint8_t prescaler = 1; - // uint8_t divisor = 2; + // bus clk + uint32_t PCLK = 48000000u; + uint8_t prescaler = 1; + uint8_t divisor = 2; - // for (prescaler = 1; prescaler <= 8; prescaler++) { - // divisor = 2; - // for (spr = 0; spr <= 8; spr++, divisor *= 2) { - // ref = PCLK / (prescaler*divisor); - // if (ref > (uint32_t)hz) - // continue; - // error = hz - ref; - // if (error < p_error) { - // ref_spr = spr; - // ref_prescaler = prescaler - 1; - // p_error = error; - // } - // } - // } + for (prescaler = 1; prescaler <= 8; prescaler++) { + divisor = 2; + for (spr = 0; spr <= 8; spr++, divisor *= 2) { + ref = PCLK / (prescaler*divisor); + if (ref > (uint32_t)hz) + continue; + error = hz - ref; + if (error < p_error) { + ref_spr = spr; + ref_prescaler = prescaler - 1; + p_error = error; + } + } + } - // // set SPPR and SPR - // obj->spi->CTAR = ((ref_prescaler & 0x7) << 4) | (ref_spr & 0xf); + // set SPPR and SPR + obj->spi->CTAR[0] = ((ref_prescaler & 0x7) << 4) | (ref_spr & 0xf); } static inline int spi_writeable(spi_t * obj) { From fbeb52d613b18148328dda99c560e9a1529990d5 Mon Sep 17 00:00:00 2001 From: Bogdan Marinescu Date: Tue, 3 Dec 2013 10:21:41 +0200 Subject: [PATCH 06/33] Added RTS/CTS flow control Currently implemented only for LPC1768. On this platform, when hardware flow control is not directly supported, it will be emulated. Also added "not_implemented.c" as a placeholder for various HAL functions that might not be implemented on all platforms (in this particular case, serial_set_flow_control). These are weak implementations that default to a "not implemented" error message. --- libraries/mbed/api/SerialBase.h | 15 +++ libraries/mbed/common/SerialBase.cpp | 20 ++++ libraries/mbed/common/not_implemented.c | 28 +++++ libraries/mbed/common/pinmap_common.c | 19 +-- libraries/mbed/hal/pinmap.h | 1 + libraries/mbed/hal/serial_api.h | 9 ++ .../hal/TARGET_NXP/TARGET_LPC176X/objects.h | 4 +- .../TARGET_NXP/TARGET_LPC176X/serial_api.c | 109 ++++++++++++++++-- 8 files changed, 185 insertions(+), 20 deletions(-) create mode 100644 libraries/mbed/common/not_implemented.c diff --git a/libraries/mbed/api/SerialBase.h b/libraries/mbed/api/SerialBase.h index 77c0d006be..f3b1a9e0d7 100644 --- a/libraries/mbed/api/SerialBase.h +++ b/libraries/mbed/api/SerialBase.h @@ -51,6 +51,13 @@ public: TxIrq }; + enum Flow { + Disabled = 0, + RTS, + CTS, + RTSCTS + }; + /** Set the transmission format used by the serial port * * @param bits The number of bits in a word (5-8; default = 8) @@ -99,6 +106,14 @@ public: /** Generate a break condition on the serial line */ void send_break(); + + /** Set the flow control type on the serial port + * + * @param type the flow control type (Disabled, RTS, CTS, RTSCTS) + * @param flow1 the first flow control pin (RTS for RTS or RTSCTS, CTS for CTS) + * @param flow2 the second flow control pin (CTS for RTSCTS) + */ + void set_flow_control(Flow type, PinName flow1=NC, PinName flow2=NC); static void _irq_handler(uint32_t id, SerialIrq irq_type); diff --git a/libraries/mbed/common/SerialBase.cpp b/libraries/mbed/common/SerialBase.cpp index 9026080a4f..10a6fb61dd 100644 --- a/libraries/mbed/common/SerialBase.cpp +++ b/libraries/mbed/common/SerialBase.cpp @@ -81,6 +81,26 @@ void SerialBase::send_break() { serial_break_clear(&_serial); } +void SerialBase::set_flow_control(Flow type, PinName flow1, PinName flow2) { + FlowControl flow_type = (FlowControl)type; + switch(type) { + case RTS: + serial_set_flow_control(&_serial, flow_type, flow1, NC); + break; + + case CTS: + serial_set_flow_control(&_serial, flow_type, NC, flow1); + break; + + case RTSCTS: + serial_set_flow_control(&_serial, flow_type, flow1, flow2); + break; + + default: + break; + } +} + } // namespace mbed #endif diff --git a/libraries/mbed/common/not_implemented.c b/libraries/mbed/common/not_implemented.c new file mode 100644 index 0000000000..53170b0dd2 --- /dev/null +++ b/libraries/mbed/common/not_implemented.c @@ -0,0 +1,28 @@ +/* mbed Microcontroller Library + * Copyright (c) 2006-2013 ARM Limited + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +// Default versions of various HAL functions that might not be implemented for some platforms. + +#include "toolchain.h" +#include "serial_api.h" +#include "error.h" + +WEAK void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, PinName txflow); +WEAK void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, PinName txflow) { + if (FlowControlNone != type) + error("hardware flow control not implemented on this platform"); +} + diff --git a/libraries/mbed/common/pinmap_common.c b/libraries/mbed/common/pinmap_common.c index 66ccf963ce..eef617fd45 100644 --- a/libraries/mbed/common/pinmap_common.c +++ b/libraries/mbed/common/pinmap_common.c @@ -44,17 +44,22 @@ uint32_t pinmap_merge(uint32_t a, uint32_t b) { return (uint32_t)NC; } -uint32_t pinmap_peripheral(PinName pin, const PinMap* map) { - if (pin == (PinName)NC) - return (uint32_t)NC; - +uint32_t pinmap_find_peripheral(PinName pin, const PinMap* map) { while (map->pin != NC) { if (map->pin == pin) return map->peripheral; map++; } - - // no mapping available - error("pinmap not found for peripheral"); return (uint32_t)NC; } + +uint32_t pinmap_peripheral(PinName pin, const PinMap* map) { + uint32_t peripheral = (uint32_t)NC; + + if (pin == (PinName)NC) + return (uint32_t)NC; + peripheral = pinmap_find_peripheral(pin, map); + if ((uint32_t)NC == peripheral) // no mapping available + error("pinmap not found for peripheral"); + return peripheral; +} diff --git a/libraries/mbed/hal/pinmap.h b/libraries/mbed/hal/pinmap.h index 0482282eb3..653d5fe9f3 100644 --- a/libraries/mbed/hal/pinmap.h +++ b/libraries/mbed/hal/pinmap.h @@ -34,6 +34,7 @@ void pin_mode (PinName pin, PinMode mode); uint32_t pinmap_peripheral(PinName pin, const PinMap* map); uint32_t pinmap_merge (uint32_t a, uint32_t b); void pinmap_pinout (PinName pin, const PinMap *map); +uint32_t pinmap_find_peripheral(PinName pin, const PinMap* map); #ifdef __cplusplus } diff --git a/libraries/mbed/hal/serial_api.h b/libraries/mbed/hal/serial_api.h index 60a3d0243d..2b0f0c4abe 100644 --- a/libraries/mbed/hal/serial_api.h +++ b/libraries/mbed/hal/serial_api.h @@ -37,6 +37,13 @@ typedef enum { TxIrq } SerialIrq; +typedef enum { + FlowControlNone, + FlowControlRTS, + FlowControlCTS, + FlowControlRTSCTS +} FlowControl; + typedef void (*uart_irq_handler)(uint32_t id, SerialIrq event); typedef struct serial_s serial_t; @@ -60,6 +67,8 @@ void serial_break_clear(serial_t *obj); void serial_pinout_tx(PinName tx); +void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, PinName txflow); + #ifdef __cplusplus } #endif diff --git a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/objects.h b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/objects.h index ace5371b46..ecbd354934 100644 --- a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/objects.h +++ b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/objects.h @@ -20,6 +20,7 @@ #include "PortNames.h" #include "PeripheralNames.h" #include "PinNames.h" +#include "gpio_object.h" #ifdef __cplusplus extern "C" { @@ -47,7 +48,6 @@ struct pwmout_s { struct serial_s { LPC_UART_TypeDef *uart; int index; - uint8_t count; }; struct analogin_s { @@ -71,8 +71,6 @@ struct spi_s { LPC_SSP_TypeDef *spi; }; -#include "gpio_object.h" - #ifdef __cplusplus } #endif diff --git a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/serial_api.c b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/serial_api.c index 96baef5689..99fb5ed8c9 100644 --- a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/serial_api.c +++ b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/serial_api.c @@ -21,6 +21,7 @@ #include "cmsis.h" #include "pinmap.h" #include "error.h" +#include "gpio_api.h" /****************************************************************************** * INITIALIZATION @@ -51,12 +52,35 @@ static const PinMap PinMap_UART_RX[] = { {NC , NC , 0} }; +static const PinMap PinMap_UART_RTS[] = { + {P0_22, UART_1, 1}, + {P2_7, UART_1, 2}, + {NC, NC, 0} +}; + +static const PinMap PinMap_UART_CTS[] = { + {P0_17, UART_1, 1}, + {P2_2, UART_1, 2}, + {NC, NC, 0} +}; + +#define UART_MCR_RTSEN_MASK (1 << 6) +#define UART_MCR_CTSEN_MASK (1 << 7) +#define UART_MCR_FLOWCTRL_MASK (UART_MCR_RTSEN_MASK | UART_MCR_CTSEN_MASK) + static uint32_t serial_irq_ids[UART_NUM] = {0}; static uart_irq_handler irq_handler; int stdio_uart_inited = 0; serial_t stdio_uart; +struct serial_global_data_s { + gpio_t sw_rts, sw_cts; + uint8_t count, initialized, irq_set_flow, irq_set_api; +}; + +static struct serial_global_data_s uart_data[UART_NUM]; + void serial_init(serial_t *obj, PinName tx, PinName rx) { int is_stdio_uart = 0; @@ -106,7 +130,11 @@ void serial_init(serial_t *obj, PinName tx, PinName rx) { case UART_2: obj->index = 2; break; case UART_3: obj->index = 3; break; } - obj->count = 0; + if (!uart_data[obj->index].initialized) { + uart_data[obj->index].sw_rts.pin = NC; + uart_data[obj->index].sw_cts.pin = NC; + uart_data[obj->index].initialized = 1; + } is_stdio_uart = (uart == STDIO_UART) ? (1) : (0); @@ -234,7 +262,9 @@ static inline void uart_irq(uint32_t iir, uint32_t index) { case 2: irq_type = RxIrq; break; default: return; } - + + if ((RxIrq == irq_type) && (uart_data[index].sw_rts.pin != NC)) + gpio_write(&uart_data[index].sw_rts, 1); if (serial_irq_ids[index] != 0) irq_handler(serial_irq_ids[index], irq_type); } @@ -249,7 +279,7 @@ void serial_irq_handler(serial_t *obj, uart_irq_handler handler, uint32_t id) { serial_irq_ids[obj->index] = id; } -void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) { +static void serial_irq_set_internal(serial_t *obj, SerialIrq irq, uint32_t enable) { IRQn_Type irq_n = (IRQn_Type)0; uint32_t vector = 0; switch ((int)obj->uart) { @@ -263,7 +293,7 @@ void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) { obj->uart->IER |= 1 << irq; NVIC_SetVector(irq_n, vector); NVIC_EnableIRQ(irq_n); - } else { // disable + } else if (uart_data[obj->index].irq_set_api + uart_data[obj->index].irq_set_flow == 0) { // disable int all_disabled = 0; SerialIrq other_irq = (irq == RxIrq) ? (TxIrq) : (RxIrq); obj->uart->IER &= ~(1 << irq); @@ -273,18 +303,30 @@ void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) { } } +void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) { + uart_data[obj->index].irq_set_api = enable; + serial_irq_set_internal(obj, irq, enable); +} + +static void serial_flow_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) { + uart_data[obj->index].irq_set_flow = enable; + serial_irq_set_internal(obj, irq, enable); +} + /****************************************************************************** * READ/WRITE ******************************************************************************/ int serial_getc(serial_t *obj) { while (!serial_readable(obj)); + if (NC != uart_data[obj->index].sw_rts.pin) + gpio_write(&uart_data[obj->index].sw_rts, 0); return obj->uart->RBR; } void serial_putc(serial_t *obj, int c) { while (!serial_writable(obj)); obj->uart->THR = c; - obj->count++; + uart_data[obj->index].count++; } int serial_readable(serial_t *obj) { @@ -293,11 +335,14 @@ int serial_readable(serial_t *obj) { int serial_writable(serial_t *obj) { int isWritable = 1; - if (obj->uart->LSR & 0x20) - obj->count = 0; - else if (obj->count >= 16) - isWritable = 0; - + if (NC != uart_data[obj->index].sw_cts.pin) + isWritable = gpio_read(&uart_data[obj->index].sw_cts) == 0; + if (isWritable) { + if (obj->uart->LSR & 0x20) + uart_data[obj->index].count = 0; + else if (uart_data[obj->index].count >= 16) + isWritable = 0; + } return isWritable; } @@ -320,3 +365,47 @@ void serial_break_clear(serial_t *obj) { obj->uart->LCR &= ~(1 << 6); } +void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, PinName txflow) { + // Only UART1 has hardware flow control on LPC176x + LPC_UART1_TypeDef *uart1 = (uint32_t)obj->uart == (uint32_t)LPC_UART1 ? LPC_UART1 : NULL; + int index = obj->index; + + // First, disable flow control completely + if (uart1) + uart1->MCR = uart1->MCR & ~UART_MCR_FLOWCTRL_MASK; + serial_flow_irq_set(obj, RxIrq, 0); + uart_data[index].sw_rts.pin = uart_data[index].sw_cts.pin = NC; + if (FlowControlNone == type) + return; + // Check type(s) of flow control to use + UARTName uart_rts = (UARTName)pinmap_find_peripheral(rxflow, PinMap_UART_RTS); + UARTName uart_cts = (UARTName)pinmap_find_peripheral(txflow, PinMap_UART_CTS); + if (((FlowControlCTS == type) || (FlowControlRTSCTS == type)) && (NC != txflow)) { + // Can this be enabled in hardware? + if ((UART_1 == uart_cts) && (NULL != uart1)) { + // Enable auto-CTS mode + uart1->MCR |= UART_MCR_CTSEN_MASK; + } else { + // Can't enable in hardware, use software emulation + gpio_init(&uart_data[index].sw_cts, txflow, PIN_INPUT); + } + } + if (((FlowControlRTS == type) || (FlowControlRTSCTS == type)) && (NC != rxflow)) { + // Enable FIFOs, trigger level of 1 char on RX FIFO + obj->uart->FCR = 1 << 0 // FIFO Enable - 0 = Disables, 1 = Enabled + | 1 << 1 // Rx Fifo Reset + | 1 << 2 // Tx Fifo Reset + | 0 << 6; // Rx irq trigger level - 0 = 1 char, 1 = 4 chars, 2 = 8 chars, 3 = 14 chars + // Can this be enabled in hardware? + if ((UART_1 == uart_rts) && (NULL != uart1)) { + // Enable auto-RTS mode + uart1->MCR |= UART_MCR_RTSEN_MASK; + } else { // can't enable in hardware, use software emulation + gpio_init(&uart_data[index].sw_rts, rxflow, PIN_OUTPUT); + gpio_write(&uart_data[index].sw_rts, 0); + // Enable RX interrupt + serial_flow_irq_set(obj, RxIrq, 1); + } + } +} + From 2ac6c4c53190a358dc75ac78e2109b273b5f6187 Mon Sep 17 00:00:00 2001 From: Bogdan Marinescu Date: Wed, 4 Dec 2013 19:46:12 +0200 Subject: [PATCH 07/33] Fixed RTS/CTS bit-banging on LPC1768 --- .../TARGET_NXP/TARGET_LPC176X/serial_api.c | 40 +++++++++++-------- 1 file changed, 24 insertions(+), 16 deletions(-) diff --git a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/serial_api.c b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/serial_api.c index 99fb5ed8c9..65c9d1f318 100644 --- a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/serial_api.c +++ b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/serial_api.c @@ -76,7 +76,7 @@ serial_t stdio_uart; struct serial_global_data_s { gpio_t sw_rts, sw_cts; - uint8_t count, initialized, irq_set_flow, irq_set_api; + uint8_t count, initialized, rx_irq_set_flow, rx_irq_set_api; }; static struct serial_global_data_s uart_data[UART_NUM]; @@ -254,7 +254,7 @@ void serial_format(serial_t *obj, int data_bits, SerialParity parity, int stop_b /****************************************************************************** * INTERRUPTS HANDLING ******************************************************************************/ -static inline void uart_irq(uint32_t iir, uint32_t index) { +static inline void uart_irq(uint32_t iir, uint32_t index, LPC_UART_TypeDef *puart) { // [Chapter 14] LPC17xx UART0/2/3: UARTn Interrupt Handling SerialIrq irq_type; switch (iir) { @@ -263,16 +263,20 @@ static inline void uart_irq(uint32_t iir, uint32_t index) { default: return; } - if ((RxIrq == irq_type) && (uart_data[index].sw_rts.pin != NC)) + if ((RxIrq == irq_type) && (NC != uart_data[index].sw_rts.pin)) { gpio_write(&uart_data[index].sw_rts, 1); + // Disable interrupt if it wasn't enabled by other part of the application + if (!uart_data[index].rx_irq_set_api) + puart->IER &= ~(1 << RxIrq); + } if (serial_irq_ids[index] != 0) irq_handler(serial_irq_ids[index], irq_type); } -void uart0_irq() {uart_irq((LPC_UART0->IIR >> 1) & 0x7, 0);} -void uart1_irq() {uart_irq((LPC_UART1->IIR >> 1) & 0x7, 1);} -void uart2_irq() {uart_irq((LPC_UART2->IIR >> 1) & 0x7, 2);} -void uart3_irq() {uart_irq((LPC_UART3->IIR >> 1) & 0x7, 3);} +void uart0_irq() {uart_irq((LPC_UART0->IIR >> 1) & 0x7, 0, (LPC_UART_TypeDef*)LPC_UART0);} +void uart1_irq() {uart_irq((LPC_UART1->IIR >> 1) & 0x7, 1, (LPC_UART_TypeDef*)LPC_UART1);} +void uart2_irq() {uart_irq((LPC_UART2->IIR >> 1) & 0x7, 2, (LPC_UART_TypeDef*)LPC_UART2);} +void uart3_irq() {uart_irq((LPC_UART3->IIR >> 1) & 0x7, 3, (LPC_UART_TypeDef*)LPC_UART3);} void serial_irq_handler(serial_t *obj, uart_irq_handler handler, uint32_t id) { irq_handler = handler; @@ -293,7 +297,7 @@ static void serial_irq_set_internal(serial_t *obj, SerialIrq irq, uint32_t enabl obj->uart->IER |= 1 << irq; NVIC_SetVector(irq_n, vector); NVIC_EnableIRQ(irq_n); - } else if (uart_data[obj->index].irq_set_api + uart_data[obj->index].irq_set_flow == 0) { // disable + } else if ((TxIrq == irq) || (uart_data[obj->index].rx_irq_set_api + uart_data[obj->index].rx_irq_set_flow == 0)) { // disable int all_disabled = 0; SerialIrq other_irq = (irq == RxIrq) ? (TxIrq) : (RxIrq); obj->uart->IER &= ~(1 << irq); @@ -304,13 +308,14 @@ static void serial_irq_set_internal(serial_t *obj, SerialIrq irq, uint32_t enabl } void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) { - uart_data[obj->index].irq_set_api = enable; + if (RxIrq == irq) + uart_data[obj->index].rx_irq_set_api = enable; serial_irq_set_internal(obj, irq, enable); } -static void serial_flow_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) { - uart_data[obj->index].irq_set_flow = enable; - serial_irq_set_internal(obj, irq, enable); +static void serial_flow_irq_set(serial_t *obj, uint32_t enable) { + uart_data[obj->index].rx_irq_set_flow = enable; + serial_irq_set_internal(obj, RxIrq, enable); } /****************************************************************************** @@ -318,9 +323,12 @@ static void serial_flow_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) { ******************************************************************************/ int serial_getc(serial_t *obj) { while (!serial_readable(obj)); - if (NC != uart_data[obj->index].sw_rts.pin) + int data = obj->uart->RBR; + if (NC != uart_data[obj->index].sw_rts.pin) { gpio_write(&uart_data[obj->index].sw_rts, 0); - return obj->uart->RBR; + obj->uart->IER |= 1 << RxIrq; + } + return data; } void serial_putc(serial_t *obj, int c) { @@ -373,8 +381,8 @@ void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, Pi // First, disable flow control completely if (uart1) uart1->MCR = uart1->MCR & ~UART_MCR_FLOWCTRL_MASK; - serial_flow_irq_set(obj, RxIrq, 0); uart_data[index].sw_rts.pin = uart_data[index].sw_cts.pin = NC; + serial_flow_irq_set(obj, 0); if (FlowControlNone == type) return; // Check type(s) of flow control to use @@ -404,7 +412,7 @@ void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, Pi gpio_init(&uart_data[index].sw_rts, rxflow, PIN_OUTPUT); gpio_write(&uart_data[index].sw_rts, 0); // Enable RX interrupt - serial_flow_irq_set(obj, RxIrq, 1); + serial_flow_irq_set(obj, 1); } } } From d0b2fb6c668b1330b58e549e39d09dcdb865efa8 Mon Sep 17 00:00:00 2001 From: Bogdan Marinescu Date: Wed, 4 Dec 2013 19:46:51 +0200 Subject: [PATCH 08/33] Added flow control test Since this requires a separate serial port connection, added this as a new attribute of the MUTs. --- .../tests/mbed/echo_flow_control/main.cpp | 34 +++++++++++++ .../host_tests/echo_flow_control.py | 48 +++++++++++++++++++ workspace_tools/host_tests/host_test.py | 14 +++++- workspace_tools/server.py | 7 +-- workspace_tools/tests.py | 11 ++++- 5 files changed, 108 insertions(+), 6 deletions(-) create mode 100644 libraries/tests/mbed/echo_flow_control/main.cpp create mode 100644 workspace_tools/host_tests/echo_flow_control.py diff --git a/libraries/tests/mbed/echo_flow_control/main.cpp b/libraries/tests/mbed/echo_flow_control/main.cpp new file mode 100644 index 0000000000..cfb098abea --- /dev/null +++ b/libraries/tests/mbed/echo_flow_control/main.cpp @@ -0,0 +1,34 @@ +#include "mbed.h" + +#if defined(TARGET_LPC1768) +#define UART_TX p9 +#define UART_RX p10 +#define FLOW_CONTROL_RTS p11 +#define FLOW_CONTROL_CTS p12 +#define RTS_CHECK_PIN p13 +#else +#error This test is not supported on this target +#endif + +Serial pc(UART_TX, UART_RX); + +#ifdef RTS_CHECK_PIN +InterruptIn in(RTS_CHECK_PIN); +DigitalOut led(LED1); +static void checker(void) { + led = !led; +} +#endif + +int main() { + char buf[256]; + + pc.set_flow_control(Serial::RTSCTS, FLOW_CONTROL_RTS, FLOW_CONTROL_CTS); +#ifdef RTS_CHECK_PIN + in.fall(checker); +#endif + while (1) { + pc.gets(buf, 256); + pc.printf("%s", buf); + } +} diff --git a/workspace_tools/host_tests/echo_flow_control.py b/workspace_tools/host_tests/echo_flow_control.py new file mode 100644 index 0000000000..b354d0b04c --- /dev/null +++ b/workspace_tools/host_tests/echo_flow_control.py @@ -0,0 +1,48 @@ +""" +mbed SDK +Copyright (c) 2011-2013 ARM Limited + +Licensed under the Apache License, Version 2.0 (the "License"); +you may not use this file except in compliance with the License. +You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + +Unless required by applicable law or agreed to in writing, software +distributed under the License is distributed on an "AS IS" BASIS, +WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +See the License for the specific language governing permissions and +limitations under the License. +""" +from host_test import Test + + +class EchoTest(Test): + def __init__(self): + Test.__init__(self) + self.mbed.init_serial() + self.mbed.extra_serial.rtscts = True + self.mbed.reset() + + def test(self): + self.mbed.flush() + self.notify("Starting the ECHO test") + TEST="longer serial test" + check = True + for i in range(1, 100): + self.mbed.extra_serial.write(TEST + "\n") + l = self.mbed.extra_serial.readline().strip() + if not l: continue + + if l != TEST: + check = False + self.notify('"%s" != "%s"' % (l, TEST)) + else: + if (i % 10) == 0: + self.notify('.') + + return check + + +if __name__ == '__main__': + EchoTest().run() diff --git a/workspace_tools/host_tests/host_test.py b/workspace_tools/host_tests/host_test.py index d0352d360b..66f4b6d74d 100644 --- a/workspace_tools/host_tests/host_test.py +++ b/workspace_tools/host_tests/host_test.py @@ -38,6 +38,9 @@ class Mbed: parser.add_option("-t", "--timeout", dest="timeout", help="Timeout", metavar="TIMEOUT") + + parser.add_option("-e", "--extra", dest="extra", + help="Extra serial port (used by some tests)", metavar="EXTRA") (self.options, _) = parser.parse_args() @@ -46,14 +49,19 @@ class Mbed: self.port = self.options.port self.disk = self.options.disk + self.extra_port = self.options.extra + self.extra_serial = None self.serial = None self.timeout = 10 if self.options.timeout is None else self.options.timeout print 'Mbed: "%s" "%s"' % (self.port, self.disk) - def init_serial(self, baud=9600): + def init_serial(self, baud=9600, extra_baud=9600): self.serial = Serial(self.port, timeout = 1) self.serial.setBaudrate(baud) + if self.extra_port: + self.extra_serial = Serial(self.extra_port, timeout = 1) + self.extra_serial.setBaudrate(extra_baud) self.flush() def reset(self): @@ -64,7 +72,9 @@ class Mbed: def flush(self): self.serial.flushInput() self.serial.flushOutput() - + if self.extra_serial: + self.extra_serial.flushInput() + self.extra_serial.flushOutput() class Test: def __init__(self): diff --git a/workspace_tools/server.py b/workspace_tools/server.py index 33a05c8aea..e5d9808540 100644 --- a/workspace_tools/server.py +++ b/workspace_tools/server.py @@ -57,9 +57,9 @@ class ProcessObserver(Thread): pass -def run_host_test(client, name, disk, port, duration): +def run_host_test(client, name, disk, port, duration, extra_serial): print "{%s}" % name, - cmd = ["python", "%s.py" % name, '-p', port, '-d', disk, '-t', str(duration)] + cmd = ["python", "%s.py" % name, '-p', port, '-d', disk, '-t', str(duration), "-e", extra_serial] proc = Popen(cmd, stdout=PIPE, cwd=HOST_TESTS) obs = ProcessObserver(proc) start = time() @@ -144,6 +144,7 @@ class Tester(BaseRequestHandler): disk = mut['disk'] port = mut['port'] + extra_serial = mut.get('extra_serial', "") target = TARGET_MAP[mut['mcu']] # Program @@ -169,7 +170,7 @@ class Tester(BaseRequestHandler): # Host test self.request.setblocking(0) - result = run_host_test(self.request, test.host_test, disk, port, duration) + result = run_host_test(self.request, test.host_test, disk, port, duration, extra_serial) self.send_result(result) diff --git a/workspace_tools/tests.py b/workspace_tools/tests.py index 9d7630f0c0..6e9d9a66ef 100644 --- a/workspace_tools/tests.py +++ b/workspace_tools/tests.py @@ -203,6 +203,15 @@ TESTS = [ "dependencies": [MBED_LIBRARIES, TEST_MBED_LIB], "automated": True, }, + { + "id": "MBED_A22", "description": "Serial echo with RTS/CTS flow control", + "source_dir": join(TEST_DIR, "mbed", "echo_flow_control"), + "dependencies": [MBED_LIBRARIES], + "automated": "True", + "host_test": "echo_flow_control", + "mcu": ["LPC1768"], + "peripherals": ["extra_serial"] + }, # Size benchmarks { @@ -392,7 +401,7 @@ TESTS = [ "dependencies": [MBED_LIBRARIES], "mcu": ["LPC1768", "LPC4088"] }, - + # CMSIS RTOS tests { "id": "CMSIS_RTOS_1", "description": "Basic", From 53cd64775d026037cc14b401d7a2d3667645e8b1 Mon Sep 17 00:00:00 2001 From: Bogdan Marinescu Date: Thu, 5 Dec 2013 16:12:47 +0200 Subject: [PATCH 09/33] Hardware flow control implementation for LPC81X --- .../hal/TARGET_NXP/TARGET_LPC81X/serial_api.c | 44 +++++++++++++++++++ 1 file changed, 44 insertions(+) diff --git a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC81X/serial_api.c b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC81X/serial_api.c index 9a98f82e87..d71d91c52d 100644 --- a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC81X/serial_api.c +++ b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC81X/serial_api.c @@ -39,6 +39,18 @@ static const SWM_Map SWM_UART_RX[] = { {2, 24}, }; +static const SWM_Map SWM_UART_RTS[] = { + {0, 16}, + {1, 24}, + {3, 0}, +}; + +static const SWM_Map SWM_UART_CTS[] = { + {0, 24}, + {2, 0}, + {3, 8} +}; + // bit flags for used UARTs static unsigned char uart_used = 0; static int get_available_uart(void) { @@ -60,6 +72,7 @@ static int get_available_uart(void) { #define TXRDY (0x01<<2) #define TXBRKEN (0x01<<1) +#define CTSEN (0x01<<9) static uint32_t UARTSysClk; @@ -278,3 +291,34 @@ void serial_break_clear(serial_t *obj) { obj->uart->CTRL &= ~TXBRKEN; } +void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, PinName txflow) { + const SWM_Map *swm_rts, *swm_cts; + uint32_t regVal_rts, regVal_cts; + + swm_rts = &SWM_UART_RTS[obj->index]; + swm_cts = &SWM_UART_CTS[obj->index]; + regVal_rts = LPC_SWM->PINASSIGN[swm_rts->n] & ~(0xFF << swm_rts->offset); + regVal_cts = LPC_SWM->PINASSIGN[swm_cts->n] & ~(0xFF << swm_cts->offset); + + if (FlowControlNone == type) { + LPC_SWM->PINASSIGN[swm_rts->n] = regVal_rts | (0xFF << swm_rts->offset); + LPC_SWM->PINASSIGN[swm_cts->n] = regVal_cts | (0xFF << swm_cts->offset); + obj->uart->CFG &= ~CTSEN; + return; + } + if ((FlowControlRTS == type || FlowControlRTSCTS == type) && (rxflow != NC)) { + LPC_SWM->PINASSIGN[swm_rts->n] = regVal_rts | (rxflow << swm_rts->offset); + if (FlowControlRTS == type) { + LPC_SWM->PINASSIGN[swm_cts->n] = regVal_cts | (0xFF << swm_cts->offset); + obj->uart->CFG &= ~CTSEN; + } + } + if ((FlowControlCTS == type || FlowControlRTSCTS == type) && (txflow != NC)) { + LPC_SWM->PINASSIGN[swm_cts->n] = regVal_cts | (txflow << swm_cts->offset); + obj->uart->CFG |= CTSEN; + if (FlowControlCTS == type) { + LPC_SWM->PINASSIGN[swm_rts->n] = regVal_rts | (0xFF << swm_rts->offset); + } + } +} + From b747181e0dabd2c90e338c32a55135ce53435815 Mon Sep 17 00:00:00 2001 From: Joey Ye Date: Fri, 6 Dec 2013 18:06:11 +0800 Subject: [PATCH 10/33] Add \r in retarget --- libraries/mbed/common/retarget.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/libraries/mbed/common/retarget.cpp b/libraries/mbed/common/retarget.cpp index 742aec0ad5..21f3379243 100644 --- a/libraries/mbed/common/retarget.cpp +++ b/libraries/mbed/common/retarget.cpp @@ -191,7 +191,7 @@ extern "C" int PREFIX(_close)(FILEHANDLE fh) { return fhc->close(); } -#if defined(__ICCARM__) +#if defined(__ICCARM__) || defined(TOOLCHAIN_GCC_ARM) extern "C" size_t __write (int fh, const unsigned char *buffer, size_t length) { #else extern "C" int PREFIX(_write)(FILEHANDLE fh, const unsigned char *buffer, unsigned int length, int mode) { @@ -201,6 +201,9 @@ extern "C" int PREFIX(_write)(FILEHANDLE fh, const unsigned char *buffer, unsign #if DEVICE_SERIAL if (!stdio_uart_inited) init_serial(); for (unsigned int i = 0; i < length; i++) { + if (buffer[i] == '\n') { + serial_putc(&stdio_uart, '\r'); + } serial_putc(&stdio_uart, buffer[i]); } #endif @@ -218,7 +221,7 @@ extern "C" int PREFIX(_write)(FILEHANDLE fh, const unsigned char *buffer, unsign #endif } -#if defined(__ICCARM__) +#if defined(__ICCARM__) || defined(TOOLCHAIN_GCC_ARM) extern "C" size_t __read (int fh, unsigned char *buffer, size_t length) { #else extern "C" int PREFIX(_read)(FILEHANDLE fh, unsigned char *buffer, unsigned int length, int mode) { From 5e9e53f934085d8a2e358d4290435ffafa20c86b Mon Sep 17 00:00:00 2001 From: 0xc0170 Date: Tue, 10 Dec 2013 15:57:43 +0100 Subject: [PATCH 11/33] PWM - changes to start the channel --- .../hal/TARGET_Freescale/TARGET_K20D5M/objects.h | 1 + .../hal/TARGET_Freescale/TARGET_K20D5M/pwmout_api.c | 11 +++++++++-- 2 files changed, 10 insertions(+), 2 deletions(-) diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/objects.h b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/objects.h index 257bc5c802..69bc95d6e1 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/objects.h +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/objects.h @@ -43,6 +43,7 @@ struct pwmout_s { __IO uint32_t *MOD; __IO uint32_t *CNT; __IO uint32_t *CnV; + __IO uint32_t *SYNC; }; struct serial_s { diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pwmout_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pwmout_api.c index 438b33056c..5936ee03b8 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pwmout_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pwmout_api.c @@ -22,11 +22,11 @@ static const PinMap PinMap_PWM[] = { // LEDs {LED_RED , PWM_3 , 3}, // PTC3, FTM0 CH2 - {LED_GREEN, PWM_5, 3}, // PTD4, FTM0 CH4 + {LED_GREEN, PWM_5, 3}, // PTD4, FTM0 CH4 {LED_BLUE , PWM_9 , 3}, // PTA2 , FTM0 CH7 // Arduino digital pinout - {D3, PWM_5 , 3}, // PTA12, FTM0 CH4 + {D3, PWM_5 , 3}, // PTD4, FTM0 CH4 {D5, PWM_7 , 3}, // PTA1 , FTM0 CH6 {D6, PWM_3 , 3}, // PTC3 , FTM0 CH2 {D9, PWM_8 , 4}, // PTD2 , FTM0 CH7 @@ -51,12 +51,18 @@ void pwmout_init(pwmout_t* obj, PinName pin) { SIM->SCGC6 |= 1 << (SIM_SCGC6_FTM0_SHIFT + ftm_n); FTM_Type *ftm = (FTM_Type *)(FTM0_BASE + 0x1000 * ftm_n); + ftm->MODE |= FTM_MODE_WPDIS_MASK; //write protection disabled + ftm->CONF |= FTM_CONF_BDMMODE(3); ftm->SC = FTM_SC_CLKS(1) | FTM_SC_PS(6); // (48)MHz / 64 = (0.75)MHz ftm->CONTROLS[ch_n].CnSC = (FTM_CnSC_MSB_MASK | FTM_CnSC_ELSB_MASK); /* No Interrupts; High True pulses on Edge Aligned PWM */ + ftm->PWMLOAD |= FTM_PWMLOAD_LDOK_MASK; //loading updated values enabled + //ftm->SYNCONF |= FTM_SYNCONF_SWRSTCNT_MASK; + ftm->MODE |= FTM_MODE_INIT_MASK; obj->CnV = &ftm->CONTROLS[ch_n].CnV; obj->MOD = &ftm->MOD; obj->CNT = &ftm->CNT; + obj->SYNC = &ftm->SYNC; // default to 20ms: standard for servos, and fine for e.g. brightness control pwmout_period_ms(obj, 20); @@ -77,6 +83,7 @@ void pwmout_write(pwmout_t* obj, float value) { *obj->CnV = (uint32_t)((float)(*obj->MOD) * value); *obj->CNT = 0; + //*obj->SYNC |= FTM_SYNC_SWSYNC_MASK; } float pwmout_read(pwmout_t* obj) { From c3d4d3079fddabe62876c28cc048cf9f4efbf5a0 Mon Sep 17 00:00:00 2001 From: Bogdan Marinescu Date: Wed, 11 Dec 2013 10:26:18 +0200 Subject: [PATCH 12/33] Added DEVICE_SERIAL_FC as an indicator for the flow control implementation --- libraries/mbed/api/SerialBase.h | 2 ++ libraries/mbed/common/SerialBase.cpp | 2 ++ libraries/mbed/common/not_implemented.c | 28 ------------------- .../hal/TARGET_NXP/TARGET_LPC176X/device.h | 1 + .../hal/TARGET_NXP/TARGET_LPC81X/device.h | 1 + 5 files changed, 6 insertions(+), 28 deletions(-) delete mode 100644 libraries/mbed/common/not_implemented.c diff --git a/libraries/mbed/api/SerialBase.h b/libraries/mbed/api/SerialBase.h index f3b1a9e0d7..57705f3262 100644 --- a/libraries/mbed/api/SerialBase.h +++ b/libraries/mbed/api/SerialBase.h @@ -107,6 +107,7 @@ public: */ void send_break(); +#if DEVICE_SERIAL_FC /** Set the flow control type on the serial port * * @param type the flow control type (Disabled, RTS, CTS, RTSCTS) @@ -114,6 +115,7 @@ public: * @param flow2 the second flow control pin (CTS for RTSCTS) */ void set_flow_control(Flow type, PinName flow1=NC, PinName flow2=NC); +#endif static void _irq_handler(uint32_t id, SerialIrq irq_type); diff --git a/libraries/mbed/common/SerialBase.cpp b/libraries/mbed/common/SerialBase.cpp index 10a6fb61dd..93cbbb9fa4 100644 --- a/libraries/mbed/common/SerialBase.cpp +++ b/libraries/mbed/common/SerialBase.cpp @@ -81,6 +81,7 @@ void SerialBase::send_break() { serial_break_clear(&_serial); } +#ifdef DEVICE_SERIAL_FC void SerialBase::set_flow_control(Flow type, PinName flow1, PinName flow2) { FlowControl flow_type = (FlowControl)type; switch(type) { @@ -100,6 +101,7 @@ void SerialBase::set_flow_control(Flow type, PinName flow1, PinName flow2) { break; } } +#endif } // namespace mbed diff --git a/libraries/mbed/common/not_implemented.c b/libraries/mbed/common/not_implemented.c deleted file mode 100644 index 53170b0dd2..0000000000 --- a/libraries/mbed/common/not_implemented.c +++ /dev/null @@ -1,28 +0,0 @@ -/* mbed Microcontroller Library - * Copyright (c) 2006-2013 ARM Limited - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -// Default versions of various HAL functions that might not be implemented for some platforms. - -#include "toolchain.h" -#include "serial_api.h" -#include "error.h" - -WEAK void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, PinName txflow); -WEAK void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, PinName txflow) { - if (FlowControlNone != type) - error("hardware flow control not implemented on this platform"); -} - diff --git a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/device.h b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/device.h index 50bd1f980a..a4646b7a00 100644 --- a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/device.h +++ b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/device.h @@ -26,6 +26,7 @@ #define DEVICE_ANALOGOUT 1 #define DEVICE_SERIAL 1 +#define DEVICE_SERIAL_FC 1 #define DEVICE_I2C 1 #define DEVICE_I2CSLAVE 1 diff --git a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC81X/device.h b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC81X/device.h index 88e5cf66b3..4ec1781cea 100644 --- a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC81X/device.h +++ b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC81X/device.h @@ -26,6 +26,7 @@ #define DEVICE_ANALOGOUT 0 #define DEVICE_SERIAL 1 +#define DEVICE_SERIAL_FC 1 #define DEVICE_I2C 1 #define DEVICE_I2CSLAVE 0 From 6b9f2079f103e0ec85c9607b68c8dc8271997dfa Mon Sep 17 00:00:00 2001 From: mazgch Date: Tue, 17 Dec 2013 11:35:23 +0100 Subject: [PATCH 13/33] Add detection of LISA-C to select CDMA protocol when using serial port. Make link monitor compatible with CDMA (no AT+COPS). --- .../CellularModem/link/LinkMonitor.cpp | 26 +++++----- .../cellular/CellularModem/link/LinkMonitor.h | 3 +- .../net/cellular/UbloxUSBModem/UbloxModem.cpp | 47 +++++++++++++++++++ 3 files changed, 64 insertions(+), 12 deletions(-) diff --git a/libraries/net/cellular/CellularModem/link/LinkMonitor.cpp b/libraries/net/cellular/CellularModem/link/LinkMonitor.cpp index 2a92c1bc32..3646b1f7aa 100644 --- a/libraries/net/cellular/CellularModem/link/LinkMonitor.cpp +++ b/libraries/net/cellular/CellularModem/link/LinkMonitor.cpp @@ -33,20 +33,24 @@ using std::sscanf; LinkMonitor::LinkMonitor(ATCommandsInterface* pIf) : m_pIf(pIf), m_rssi(0), m_registrationState(REGISTRATION_STATE_UNKNOWN), m_bearer(BEARER_UNKNOWN) { - + m_gsm = true; } -int LinkMonitor::init() +int LinkMonitor::init(bool gsm) { - // we need to make sure that we setup the operator selection to be in 'numeric' format. - // i.e. it is made up of a network and country code when returned by the modem e.g. Operator = 23415. This allows easy logic parsing for - // setting up other network parameters in future. - DBG("LinkMonitor::init() being called. This should only happen once: executinging AT+COPS=0,2"); - int ret = m_pIf->executeSimple("AT+COPS=0,2", NULL, DEFAULT_TIMEOUT); //Configure to set the operator string to Country Code and mobile network code - if(ret != OK) + m_gsm = gsm; + if (m_gsm) { - WARN(" NET_PROTOCOL error from sending the AT+COPS command to the modem. "); - return NET_PROTOCOL; + // we need to make sure that we setup the operator selection to be in 'numeric' format. + // i.e. it is made up of a network and country code when returned by the modem e.g. Operator = 23415. This allows easy logic parsing for + // setting up other network parameters in future. + DBG("LinkMonitor::init() being called. This should only happen once: executinging AT+COPS=0,2"); + int ret = m_pIf->executeSimple("AT+COPS=0,2", NULL, DEFAULT_TIMEOUT); //Configure to set the operator string to Country Code and mobile network code + if(ret != OK) + { + WARN(" NET_PROTOCOL error from sending the AT+COPS command to the modem. "); + return NET_PROTOCOL; + } } return OK; } @@ -136,7 +140,7 @@ int LinkMonitor::getState(int* pRssi, REGISTRATION_STATE* pRegistrationState, BE m_rssi = 0; m_registrationState = REGISTRATION_STATE_UNKNOWN; m_bearer = BEARER_UNKNOWN; - int ret = m_pIf->execute("AT+CREG?;+COPS?;+CSQ", this, NULL, DEFAULT_TIMEOUT); //Configure to get registration info & get it; get signal quality + int ret = m_pIf->execute(m_gsm ? "AT+CREG?;+COPS?;+CSQ" : "AT+CREG?;+CSQ", this, NULL, DEFAULT_TIMEOUT); //Configure to get registration info & get it; get signal quality if(ret != OK) { return NET_PROTOCOL; diff --git a/libraries/net/cellular/CellularModem/link/LinkMonitor.h b/libraries/net/cellular/CellularModem/link/LinkMonitor.h index bca59b522f..527e3581d3 100644 --- a/libraries/net/cellular/CellularModem/link/LinkMonitor.h +++ b/libraries/net/cellular/CellularModem/link/LinkMonitor.h @@ -39,7 +39,7 @@ public: /** Initialize monitor */ - int init(); + int init(bool gsm = true); /** Registration State */ @@ -82,6 +82,7 @@ private: ATCommandsInterface* m_pIf; int m_rssi; + bool m_gsm; REGISTRATION_STATE m_registrationState; BEARER m_bearer; diff --git a/libraries/net/cellular/UbloxUSBModem/UbloxModem.cpp b/libraries/net/cellular/UbloxUSBModem/UbloxModem.cpp index 055cb28570..4b3939ecfa 100644 --- a/libraries/net/cellular/UbloxUSBModem/UbloxModem.cpp +++ b/libraries/net/cellular/UbloxUSBModem/UbloxModem.cpp @@ -45,6 +45,36 @@ UbloxModem::UbloxModem(IOStream* atStream, IOStream* pppStream) : { } + +class AtiProcessor : public IATCommandsProcessor +{ +public: + AtiProcessor() + { + i = 0; + str[0] = '\0'; + } + const char* getInfo(void) { return str; } +private: + virtual int onNewATResponseLine(ATCommandsInterface* pInst, const char* line) + { + int l = strlen(line); + if (i + l + 2 > sizeof(str)) + return NET_OVERFLOW; + if (i) str[i++] = ','; + strcat(&str[i], line); + i += l; + return OK; + } + virtual int onNewEntryPrompt(ATCommandsInterface* pInst) + { + return OK; + } +protected: + char str[256]; + int i; +}; + class CREGProcessor : public IATCommandsProcessor { public: @@ -309,6 +339,22 @@ int UbloxModem::init() } ATCommandsInterface::ATResult result; + AtiProcessor atiProcessor; + do + { + ret = m_at.execute("ATI", &atiProcessor, &result); + } + while (ret != OK); + { + const char* info = atiProcessor.getInfo(); + DBG("Modem Identification [%s]", info); + if (strstr(info, "LISA-C200")) + { + m_gsm = false; // it is CDMA modem + m_onePort = true; // force use of only one port + } + } + CREGProcessor cregProcessor(m_gsm); //Wait for network registration do @@ -393,6 +439,7 @@ int UbloxModem::getLinkState(int* pRssi, LinkMonitor::REGISTRATION_STATE* pRegis if(!m_linkMonitorInit) { ret = m_linkMonitor.init(); + ret = m_linkMonitor.init(m_gsm); if(ret) { return ret; From b74e0c8b399b29842b802f89bb133a0f2f60ca92 Mon Sep 17 00:00:00 2001 From: Bogdan Marinescu Date: Wed, 18 Dec 2013 16:03:27 +0200 Subject: [PATCH 14/33] mbed-tools package improvements - install all the needed components - use a customized version of private_settings.py. Projects using mbed-tools will be able to use mbed_settings.py instead of private_settings.py. This ensures compatibility with the current structure. --- MANIFEST | 96 ------------------------------------- MANIFEST.in | 3 +- setup.py | 26 +++++++++- workspace_tools/settings.py | 2 +- 4 files changed, 28 insertions(+), 99 deletions(-) delete mode 100644 MANIFEST diff --git a/MANIFEST b/MANIFEST deleted file mode 100644 index 3d917d208a..0000000000 --- a/MANIFEST +++ /dev/null @@ -1,96 +0,0 @@ -# file GENERATED by distutils, do NOT edit -LICENSE -setup.py -workspace_tools/__init__.py -workspace_tools/__init__.pyc -workspace_tools/autotest.py -workspace_tools/build.py -workspace_tools/build_api.py -workspace_tools/build_release.py -workspace_tools/client.py -workspace_tools/export_test.py -workspace_tools/hooks.py -workspace_tools/libraries.py -workspace_tools/make.py -workspace_tools/options.py -workspace_tools/patch.py -workspace_tools/paths.py -workspace_tools/project.py -workspace_tools/server.py -workspace_tools/settings.py -workspace_tools/size.py -workspace_tools/syms.py -workspace_tools/synch.py -workspace_tools/targets.py -workspace_tools/tests.py -workspace_tools/utils.py -workspace_tools/data/__init__.py -workspace_tools/data/example_test_spec.json -workspace_tools/data/support.py -workspace_tools/data/rpc/RPCClasses.h -workspace_tools/data/rpc/class.cpp -workspace_tools/dev/__init__.py -workspace_tools/dev/dsp_fir.py -workspace_tools/dev/rpc_classes.py -workspace_tools/export/__init__.py -workspace_tools/export/codered.py -workspace_tools/export/codered_lpc1768_cproject.tmpl -workspace_tools/export/codered_lpc1768_project.tmpl -workspace_tools/export/codered_lpc4088_cproject.tmpl -workspace_tools/export/codered_lpc4088_project.tmpl -workspace_tools/export/codesourcery.py -workspace_tools/export/codesourcery_lpc1768.tmpl -workspace_tools/export/ds5_5.py -workspace_tools/export/ds5_5_lpc11u24.cproject.tmpl -workspace_tools/export/ds5_5_lpc11u24.launch.tmpl -workspace_tools/export/ds5_5_lpc11u24.project.tmpl -workspace_tools/export/ds5_5_lpc1768.cproject.tmpl -workspace_tools/export/ds5_5_lpc1768.launch.tmpl -workspace_tools/export/ds5_5_lpc1768.project.tmpl -workspace_tools/export/exporters.py -workspace_tools/export/gcc_arm_lpc1768.tmpl -workspace_tools/export/gccarm.py -workspace_tools/export/iar.ewp.tmpl -workspace_tools/export/iar.eww.tmpl -workspace_tools/export/iar.py -workspace_tools/export/uvision4.py -workspace_tools/export/uvision4_kl25z.uvopt.tmpl -workspace_tools/export/uvision4_kl25z.uvproj.tmpl -workspace_tools/export/uvision4_lpc1114.uvopt.tmpl -workspace_tools/export/uvision4_lpc1114.uvproj.tmpl -workspace_tools/export/uvision4_lpc11c24.uvopt.tmpl -workspace_tools/export/uvision4_lpc11c24.uvproj.tmpl -workspace_tools/export/uvision4_lpc11u24.uvopt.tmpl -workspace_tools/export/uvision4_lpc11u24.uvproj.tmpl -workspace_tools/export/uvision4_lpc1347.uvopt.tmpl -workspace_tools/export/uvision4_lpc1347.uvproj.tmpl -workspace_tools/export/uvision4_lpc1768.uvopt.tmpl -workspace_tools/export/uvision4_lpc1768.uvproj.tmpl -workspace_tools/export/uvision4_lpc4088.uvopt.tmpl -workspace_tools/export/uvision4_lpc4088.uvproj.tmpl -workspace_tools/export/uvision4_lpc812.uvopt.tmpl -workspace_tools/export/uvision4_lpc812.uvproj.tmpl -workspace_tools/host_tests/__init__.py -workspace_tools/host_tests/echo.py -workspace_tools/host_tests/host_test.py -workspace_tools/host_tests/mbedrpc.py -workspace_tools/host_tests/net_test.py -workspace_tools/host_tests/rpc.py -workspace_tools/host_tests/tcpecho_client.py -workspace_tools/host_tests/tcpecho_server.py -workspace_tools/host_tests/tcpecho_server_loop.py -workspace_tools/host_tests/udpecho_client.py -workspace_tools/host_tests/udpecho_server.py -workspace_tools/host_tests/example/BroadcastReceive.py -workspace_tools/host_tests/example/BroadcastSend.py -workspace_tools/host_tests/example/MulticastReceive.py -workspace_tools/host_tests/example/MulticastSend.py -workspace_tools/host_tests/example/TCPEchoClient.py -workspace_tools/host_tests/example/TCPEchoServer.py -workspace_tools/host_tests/example/UDPEchoClient.py -workspace_tools/host_tests/example/UDPEchoServer.py -workspace_tools/host_tests/example/__init__.py -workspace_tools/toolchains/__init__.py -workspace_tools/toolchains/arm.py -workspace_tools/toolchains/gcc.py -workspace_tools/toolchains/iar.py diff --git a/MANIFEST.in b/MANIFEST.in index 8294764a5c..17993153c5 100644 --- a/MANIFEST.in +++ b/MANIFEST.in @@ -1,2 +1,3 @@ graft workspace_tools -include __init__.py LICENSE +recursive-exclude workspace_tools *.pyc +include LICENSE diff --git a/setup.py b/setup.py index c63fadee2e..2978dbdd01 100644 --- a/setup.py +++ b/setup.py @@ -4,6 +4,10 @@ PyPI package for the Mbed SDK """ from distutils.core import setup +from setuptools import find_packages +from os.path import isfile, join +from tempfile import TemporaryFile +from shutil import copyfileobj LICENSE = open('LICENSE').read() DESCRIPTION = """A set of Python scripts that can be used to compile programs written on top of the `mbed framework`_. It can also be used to export mbed projects to other build systems and IDEs (uVision, IAR, makefiles). @@ -12,8 +16,21 @@ DESCRIPTION = """A set of Python scripts that can be used to compile programs wr OWNER_NAMES = 'emilmont, bogdanm' OWNER_EMAILS = 'Emilio.Monti@arm.com, Bogdan.Marinescu@arm.com' +# If private_settings.py exists in workspace_tools, read it in a temporary file +# so it can be restored later +private_settings = join('workspace_tools', 'private_settings.py') +backup = None +if isfile(private_settings): + backup = TemporaryFile() + with open(private_settings, "rb") as f: + copyfileobj(f, backup) + +# Create the correct private_settings.py for the distribution +with open(private_settings, "wt") as f: + f.write("from mbed_settings import *\n") + setup(name='mbed-tools', - version='0.1.7', + version='0.1.14', description='Build and test system for mbed', long_description=DESCRIPTION, author=OWNER_NAMES, @@ -21,4 +38,11 @@ setup(name='mbed-tools', maintainer=OWNER_NAMES, maintainer_email=OWNER_EMAILS, url='https://github.com/mbedmicro/mbed', + packages=find_packages(), license=LICENSE) + +# Restore previous private_settings if needed +if backup: + backup.seek(0) + with open(private_settings, "wb") as f: + copyfileobj(backup, f) diff --git a/workspace_tools/settings.py b/workspace_tools/settings.py index 32b18f7a3f..4f65c4729e 100644 --- a/workspace_tools/settings.py +++ b/workspace_tools/settings.py @@ -106,4 +106,4 @@ try: # settings file stored in the repository from workspace_tools.private_settings import * except ImportError: - print '[WARNING] Using default settings. Define you settings in the file "workspace_tools/private_settings.py"' + print '[WARNING] Using default settings. Define you settings in the file "workspace_tools/private_settings.py" or in "./mbed_settings.py"' From 9213137011206cda95e66699e2a148dbca6b607c Mon Sep 17 00:00:00 2001 From: Joey Ye Date: Thu, 19 Dec 2013 09:30:18 +0800 Subject: [PATCH 15/33] Discard \r change as pull request rejected --- libraries/mbed/common/retarget.cpp | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/libraries/mbed/common/retarget.cpp b/libraries/mbed/common/retarget.cpp index 21f3379243..742aec0ad5 100644 --- a/libraries/mbed/common/retarget.cpp +++ b/libraries/mbed/common/retarget.cpp @@ -191,7 +191,7 @@ extern "C" int PREFIX(_close)(FILEHANDLE fh) { return fhc->close(); } -#if defined(__ICCARM__) || defined(TOOLCHAIN_GCC_ARM) +#if defined(__ICCARM__) extern "C" size_t __write (int fh, const unsigned char *buffer, size_t length) { #else extern "C" int PREFIX(_write)(FILEHANDLE fh, const unsigned char *buffer, unsigned int length, int mode) { @@ -201,9 +201,6 @@ extern "C" int PREFIX(_write)(FILEHANDLE fh, const unsigned char *buffer, unsign #if DEVICE_SERIAL if (!stdio_uart_inited) init_serial(); for (unsigned int i = 0; i < length; i++) { - if (buffer[i] == '\n') { - serial_putc(&stdio_uart, '\r'); - } serial_putc(&stdio_uart, buffer[i]); } #endif @@ -221,7 +218,7 @@ extern "C" int PREFIX(_write)(FILEHANDLE fh, const unsigned char *buffer, unsign #endif } -#if defined(__ICCARM__) || defined(TOOLCHAIN_GCC_ARM) +#if defined(__ICCARM__) extern "C" size_t __read (int fh, unsigned char *buffer, size_t length) { #else extern "C" int PREFIX(_read)(FILEHANDLE fh, unsigned char *buffer, unsigned int length, int mode) { From a3465b5eacb4d383e742abfecedeadbd637b2b24 Mon Sep 17 00:00:00 2001 From: Yihui Xiong Date: Thu, 19 Dec 2013 12:31:31 +0800 Subject: [PATCH 16/33] fix 16bit timer pwm output --- .../hal/TARGET_NXP/TARGET_LPC11UXX/pwmout_api.c | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC11UXX/pwmout_api.c b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC11UXX/pwmout_api.c index 718d7339cc..5cb7e13abe 100644 --- a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC11UXX/pwmout_api.c +++ b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC11UXX/pwmout_api.c @@ -66,8 +66,6 @@ static LPC_CTxxBx_Type *Timers[4] = { LPC_CT32B0, LPC_CT32B1 }; -static unsigned int pwm_clock_mhz; - void pwmout_init(pwmout_t* obj, PinName pin) { // determine the channel PWMName pwm = (PWMName)pinmap_peripheral(pin, PinMap_PWM); @@ -92,8 +90,6 @@ void pwmout_init(pwmout_t* obj, PinName pin) { /* Reset Functionality on MR3 controlling the PWM period */ timer->MCR = 1 << 10; - pwm_clock_mhz = SystemCoreClock / 1000000; - // default to 20ms: standard for servos, and fine for e.g. brightness control pwmout_period_ms(obj, 20); pwmout_write (obj, 0); @@ -141,11 +137,18 @@ void pwmout_period_ms(pwmout_t* obj, int ms) { // Set the PWM period, keeping the duty cycle the same. void pwmout_period_us(pwmout_t* obj, int us) { int i = 0; - uint32_t period_ticks = pwm_clock_mhz * us; + uint32_t period_ticks = (uint32_t)(((uint64_t)SystemCoreClock * (uint64_t)us) / (uint64_t)1000000); timer_mr tid = pwm_timer_map[obj->pwm]; LPC_CTxxBx_Type *timer = Timers[tid.timer]; uint32_t old_period_ticks = timer->MR3; + + // for 16bit timer, set prescaler to avoid overflow + uint16_t high_period_ticks = period_ticks >> 16; + if ((high_period_ticks) && (timer == LPC_CT16B0 || timer == LPC_CT16B1)) { + timer->PR = high_period_ticks; + period_ticks /= (high_period_ticks + 1); + } timer->TCR = TCR_RESET; timer->MR3 = period_ticks; @@ -169,13 +172,14 @@ void pwmout_pulsewidth_ms(pwmout_t* obj, int ms) { } void pwmout_pulsewidth_us(pwmout_t* obj, int us) { - uint32_t t_on = (uint32_t)(((uint64_t)SystemCoreClock * (uint64_t)us) / (uint64_t)1000000); timer_mr tid = pwm_timer_map[obj->pwm]; LPC_CTxxBx_Type *timer = Timers[tid.timer]; + uint32_t t_on = (uint32_t)(((uint64_t)SystemCoreClock * (uint64_t)us) / (uint64_t)1000000 / (timer->PR + 1)); timer->TCR = TCR_RESET; if (t_on > timer->MR3) { pwmout_period_us(obj, us); + t_on = (uint32_t)(((uint64_t)SystemCoreClock * (uint64_t)us) / (uint64_t)1000000 / (timer->PR + 1)); } uint32_t t_off = timer->MR3 - t_on; timer->MR[tid.mr] = t_off; From bb8ed20a47a2b4e73d7c974d743452bba5098664 Mon Sep 17 00:00:00 2001 From: Bogdan Marinescu Date: Wed, 11 Dec 2013 16:31:59 +0200 Subject: [PATCH 17/33] LPC1768 flow control fixes - Disable TX buffer, this isn't compatible with the software CTS implementation - Properly set hardware RTS/CTS pins when possible - Modified test to use hardware CTS and software RTS --- .../TARGET_NXP/TARGET_LPC176X/serial_api.c | 33 ++++++++----------- .../tests/mbed/echo_flow_control/main.cpp | 8 ++--- workspace_tools/build.py | 2 +- 3 files changed, 19 insertions(+), 24 deletions(-) diff --git a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/serial_api.c b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/serial_api.c index 65c9d1f318..786048471a 100644 --- a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/serial_api.c +++ b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC176X/serial_api.c @@ -68,15 +68,15 @@ static const PinMap PinMap_UART_CTS[] = { #define UART_MCR_CTSEN_MASK (1 << 7) #define UART_MCR_FLOWCTRL_MASK (UART_MCR_RTSEN_MASK | UART_MCR_CTSEN_MASK) -static uint32_t serial_irq_ids[UART_NUM] = {0}; static uart_irq_handler irq_handler; int stdio_uart_inited = 0; serial_t stdio_uart; struct serial_global_data_s { + uint32_t serial_irq_id; gpio_t sw_rts, sw_cts; - uint8_t count, initialized, rx_irq_set_flow, rx_irq_set_api; + uint8_t rx_irq_set_flow, rx_irq_set_api; }; static struct serial_global_data_s uart_data[UART_NUM]; @@ -130,11 +130,9 @@ void serial_init(serial_t *obj, PinName tx, PinName rx) { case UART_2: obj->index = 2; break; case UART_3: obj->index = 3; break; } - if (!uart_data[obj->index].initialized) { - uart_data[obj->index].sw_rts.pin = NC; - uart_data[obj->index].sw_cts.pin = NC; - uart_data[obj->index].initialized = 1; - } + uart_data[obj->index].sw_rts.pin = NC; + uart_data[obj->index].sw_cts.pin = NC; + serial_set_flow_control(obj, FlowControlNone, NC, NC); is_stdio_uart = (uart == STDIO_UART) ? (1) : (0); @@ -145,7 +143,7 @@ void serial_init(serial_t *obj, PinName tx, PinName rx) { } void serial_free(serial_t *obj) { - serial_irq_ids[obj->index] = 0; + uart_data[obj->index].serial_irq_id = 0; } // serial_baud @@ -262,15 +260,15 @@ static inline void uart_irq(uint32_t iir, uint32_t index, LPC_UART_TypeDef *puar case 2: irq_type = RxIrq; break; default: return; } - if ((RxIrq == irq_type) && (NC != uart_data[index].sw_rts.pin)) { gpio_write(&uart_data[index].sw_rts, 1); // Disable interrupt if it wasn't enabled by other part of the application if (!uart_data[index].rx_irq_set_api) puart->IER &= ~(1 << RxIrq); } - if (serial_irq_ids[index] != 0) - irq_handler(serial_irq_ids[index], irq_type); + if (uart_data[index].serial_irq_id != 0) + if ((irq_type != RxIrq) || (uart_data[index].rx_irq_set_api)) + irq_handler(uart_data[index].serial_irq_id, irq_type); } void uart0_irq() {uart_irq((LPC_UART0->IIR >> 1) & 0x7, 0, (LPC_UART_TypeDef*)LPC_UART0);} @@ -280,7 +278,7 @@ void uart3_irq() {uart_irq((LPC_UART3->IIR >> 1) & 0x7, 3, (LPC_UART_TypeDef*)LP void serial_irq_handler(serial_t *obj, uart_irq_handler handler, uint32_t id) { irq_handler = handler; - serial_irq_ids[obj->index] = id; + uart_data[obj->index].serial_irq_id = id; } static void serial_irq_set_internal(serial_t *obj, SerialIrq irq, uint32_t enable) { @@ -334,7 +332,6 @@ int serial_getc(serial_t *obj) { void serial_putc(serial_t *obj, int c) { while (!serial_writable(obj)); obj->uart->THR = c; - uart_data[obj->index].count++; } int serial_readable(serial_t *obj) { @@ -345,12 +342,8 @@ int serial_writable(serial_t *obj) { int isWritable = 1; if (NC != uart_data[obj->index].sw_cts.pin) isWritable = gpio_read(&uart_data[obj->index].sw_cts) == 0; - if (isWritable) { - if (obj->uart->LSR & 0x20) - uart_data[obj->index].count = 0; - else if (uart_data[obj->index].count >= 16) - isWritable = 0; - } + if (isWritable) + isWritable = obj->uart->LSR & 0x40; return isWritable; } @@ -393,6 +386,7 @@ void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, Pi if ((UART_1 == uart_cts) && (NULL != uart1)) { // Enable auto-CTS mode uart1->MCR |= UART_MCR_CTSEN_MASK; + pinmap_pinout(txflow, PinMap_UART_CTS); } else { // Can't enable in hardware, use software emulation gpio_init(&uart_data[index].sw_cts, txflow, PIN_INPUT); @@ -408,6 +402,7 @@ void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, Pi if ((UART_1 == uart_rts) && (NULL != uart1)) { // Enable auto-RTS mode uart1->MCR |= UART_MCR_RTSEN_MASK; + pinmap_pinout(rxflow, PinMap_UART_RTS); } else { // can't enable in hardware, use software emulation gpio_init(&uart_data[index].sw_rts, rxflow, PIN_OUTPUT); gpio_write(&uart_data[index].sw_rts, 0); diff --git a/libraries/tests/mbed/echo_flow_control/main.cpp b/libraries/tests/mbed/echo_flow_control/main.cpp index cfb098abea..016d0040e4 100644 --- a/libraries/tests/mbed/echo_flow_control/main.cpp +++ b/libraries/tests/mbed/echo_flow_control/main.cpp @@ -1,11 +1,11 @@ #include "mbed.h" #if defined(TARGET_LPC1768) -#define UART_TX p9 -#define UART_RX p10 -#define FLOW_CONTROL_RTS p11 +#define UART_TX p13 +#define UART_RX p14 +#define FLOW_CONTROL_RTS p30 #define FLOW_CONTROL_CTS p12 -#define RTS_CHECK_PIN p13 +#define RTS_CHECK_PIN p15 #else #error This test is not supported on this target #endif diff --git a/workspace_tools/build.py b/workspace_tools/build.py index bcd11c6138..f3644ba118 100644 --- a/workspace_tools/build.py +++ b/workspace_tools/build.py @@ -23,7 +23,7 @@ from os.path import join, abspath, dirname # Be sure that the tools directory is in the search path ROOT = abspath(join(dirname(__file__), "..")) -sys.path.append(ROOT) +sys.path.insert(0, ROOT) from workspace_tools.toolchains import TOOLCHAINS from workspace_tools.targets import TARGET_NAMES, TARGET_MAP From e162e96245d4042ff81d08a39bfe6aa554de94ea Mon Sep 17 00:00:00 2001 From: Bogdan Marinescu Date: Thu, 19 Dec 2013 15:02:57 +0200 Subject: [PATCH 18/33] Always use the local version of workspace_tools This ensures compatibility with the mbed-tools package. --- workspace_tools/autotest.py | 2 +- workspace_tools/build_release.py | 2 +- workspace_tools/export_test.py | 2 +- workspace_tools/host_tests/tcpecho_server_loop.py | 2 +- workspace_tools/make.py | 2 +- workspace_tools/project.py | 2 +- workspace_tools/server.py | 2 +- workspace_tools/size.py | 2 +- workspace_tools/synch.py | 2 +- 9 files changed, 9 insertions(+), 9 deletions(-) diff --git a/workspace_tools/autotest.py b/workspace_tools/autotest.py index 2357ea5f55..9a0a51a5e2 100644 --- a/workspace_tools/autotest.py +++ b/workspace_tools/autotest.py @@ -21,7 +21,7 @@ import datetime from time import time ROOT = abspath(join(dirname(__file__), "..")) -sys.path.append(ROOT) +sys.path.insert(0, ROOT) from workspace_tools.build_api import build_project, build_mbed_libs from workspace_tools.tests import TEST_MAP, GROUPS diff --git a/workspace_tools/build_release.py b/workspace_tools/build_release.py index d8a3b4839b..3092f5d5a4 100644 --- a/workspace_tools/build_release.py +++ b/workspace_tools/build_release.py @@ -20,7 +20,7 @@ from os.path import join, abspath, dirname # Be sure that the tools directory is in the search path ROOT = abspath(join(dirname(__file__), "..")) -sys.path.append(ROOT) +sys.path.insert(0, ROOT) from workspace_tools.build_api import build_mbed_libs from workspace_tools.targets import TARGET_MAP diff --git a/workspace_tools/export_test.py b/workspace_tools/export_test.py index ad27478223..ff414afc13 100644 --- a/workspace_tools/export_test.py +++ b/workspace_tools/export_test.py @@ -17,7 +17,7 @@ limitations under the License. import sys from os.path import join, abspath, dirname, exists ROOT = abspath(join(dirname(__file__), "..")) -sys.path.append(ROOT) +sys.path.insert(0, ROOT) from shutil import move diff --git a/workspace_tools/host_tests/tcpecho_server_loop.py b/workspace_tools/host_tests/tcpecho_server_loop.py index 73df00ec90..df483974aa 100644 --- a/workspace_tools/host_tests/tcpecho_server_loop.py +++ b/workspace_tools/host_tests/tcpecho_server_loop.py @@ -18,7 +18,7 @@ limitations under the License. import sys from os.path import join, abspath, dirname ROOT = abspath(join(dirname(__file__), "..", "..")) -sys.path.append(ROOT) +sys.path.insert(0, ROOT) from workspace_tools.private_settings import LOCALHOST from SocketServer import BaseRequestHandler, TCPServer diff --git a/workspace_tools/make.py b/workspace_tools/make.py index 9366db922a..62a26be085 100644 --- a/workspace_tools/make.py +++ b/workspace_tools/make.py @@ -25,7 +25,7 @@ from time import sleep # Be sure that the tools directory is in the search path ROOT = abspath(join(dirname(__file__), "..")) -sys.path.append(ROOT) +sys.path.insert(0, ROOT) from workspace_tools.options import get_default_options_parser from workspace_tools.build_api import build_project diff --git a/workspace_tools/project.py b/workspace_tools/project.py index 8296fd3ff2..e62e1a5396 100644 --- a/workspace_tools/project.py +++ b/workspace_tools/project.py @@ -1,7 +1,7 @@ import sys from os.path import join, abspath, dirname, exists ROOT = abspath(join(dirname(__file__), "..")) -sys.path.append(ROOT) +sys.path.insert(0, ROOT) from shutil import move from optparse import OptionParser diff --git a/workspace_tools/server.py b/workspace_tools/server.py index e5d9808540..f9551036df 100644 --- a/workspace_tools/server.py +++ b/workspace_tools/server.py @@ -27,7 +27,7 @@ import json # Be sure that the tools directory is in the search path ROOT = abspath(join(dirname(__file__), "..")) -sys.path.append(ROOT) +sys.path.insert(0, ROOT) from workspace_tools.utils import delete_dir_files from workspace_tools.settings import * diff --git a/workspace_tools/size.py b/workspace_tools/size.py index fe7a025ba2..8ba897d43f 100644 --- a/workspace_tools/size.py +++ b/workspace_tools/size.py @@ -21,7 +21,7 @@ import csv from collections import defaultdict ROOT = abspath(join(dirname(__file__), "..")) -sys.path.append(ROOT) +sys.path.insert(0, ROOT) from workspace_tools.paths import BUILD_DIR, TOOLS_DATA from workspace_tools.settings import GCC_ARM_PATH diff --git a/workspace_tools/synch.py b/workspace_tools/synch.py index d3936a5048..16123f23d5 100644 --- a/workspace_tools/synch.py +++ b/workspace_tools/synch.py @@ -29,7 +29,7 @@ import re import string ROOT = abspath(join(dirname(__file__), "..")) -sys.path.append(ROOT) +sys.path.insert(0, ROOT) from workspace_tools.settings import MBED_ORG_PATH, MBED_ORG_USER, BUILD_DIR from workspace_tools.paths import LIB_DIR From 5f62a399db433ab8265a3fb708366cb87846954c Mon Sep 17 00:00:00 2001 From: Bogdan Marinescu Date: Thu, 19 Dec 2013 15:05:17 +0200 Subject: [PATCH 19/33] Added preliminary printf() support to RawSerial --- libraries/mbed/api/RawSerial.h | 10 ++++++++++ libraries/mbed/common/RawSerial.cpp | 31 +++++++++++++++++++++++++++++ 2 files changed, 41 insertions(+) diff --git a/libraries/mbed/api/RawSerial.h b/libraries/mbed/api/RawSerial.h index 83c3ecc129..a5182bb64f 100644 --- a/libraries/mbed/api/RawSerial.h +++ b/libraries/mbed/api/RawSerial.h @@ -71,6 +71,16 @@ public: * @returns The char read from the serial port */ int getc(); + + /** Write a string to the serial port + * + * @param str The string to write + * + * @returns 0 if the write succeeds, EOF for error + */ + int puts(const char *str); + + int printf(const char *format, ...); }; } // namespace mbed diff --git a/libraries/mbed/common/RawSerial.cpp b/libraries/mbed/common/RawSerial.cpp index 09225d520d..dc5db7a3fc 100644 --- a/libraries/mbed/common/RawSerial.cpp +++ b/libraries/mbed/common/RawSerial.cpp @@ -15,9 +15,12 @@ */ #include "RawSerial.h" #include "wait_api.h" +#include #if DEVICE_SERIAL +#define STRING_STACK_LIMIT 120 + namespace mbed { RawSerial::RawSerial(PinName tx, PinName rx) : SerialBase(tx, rx) { @@ -31,6 +34,34 @@ int RawSerial::putc(int c) { return _base_putc(c); } +int RawSerial::puts(const char *str) { + while (*str) + putc(*str ++); + return 0; +} + +// Experimental support for printf in RawSerial. No Stream inheritance +// means we can't call printf() directly, so we use sprintf() instead. +// We only call malloc() for the sprintf() buffer if the buffer +// length is above a certain threshold, otherwise we use just the stack. +int RawSerial::printf(const char *format, ...) { + std::va_list arg; + va_start(arg, format); + int len = vsnprintf(NULL, 0, format, arg); + if (len < STRING_STACK_LIMIT) { + char temp[STRING_STACK_LIMIT]; + vsprintf(temp, format, arg); + puts(temp); + } else { + char *temp = new char[len + 1]; + vsprintf(temp, format, arg); + puts(temp); + delete[] temp; + } + va_end(arg); + return len; +} + } // namespace mbed #endif From 4b4b986cdb24f240f416b7538e9766bec33be31f Mon Sep 17 00:00:00 2001 From: Bogdan Marinescu Date: Thu, 19 Dec 2013 15:05:36 +0200 Subject: [PATCH 20/33] Changed flow control test pin assignments --- libraries/tests/mbed/echo_flow_control/main.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/tests/mbed/echo_flow_control/main.cpp b/libraries/tests/mbed/echo_flow_control/main.cpp index 016d0040e4..d0b6c1b20b 100644 --- a/libraries/tests/mbed/echo_flow_control/main.cpp +++ b/libraries/tests/mbed/echo_flow_control/main.cpp @@ -1,11 +1,11 @@ #include "mbed.h" #if defined(TARGET_LPC1768) -#define UART_TX p13 -#define UART_RX p14 +#define UART_TX p9 +#define UART_RX p10 #define FLOW_CONTROL_RTS p30 -#define FLOW_CONTROL_CTS p12 -#define RTS_CHECK_PIN p15 +#define FLOW_CONTROL_CTS p29 +#define RTS_CHECK_PIN p8 #else #error This test is not supported on this target #endif From 425e197ba60d8846be1d5e5056f0800afc2c3a5c Mon Sep 17 00:00:00 2001 From: Bogdan Marinescu Date: Thu, 19 Dec 2013 17:59:24 +0200 Subject: [PATCH 21/33] Fix missing case in flow control code --- libraries/mbed/common/SerialBase.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/mbed/common/SerialBase.cpp b/libraries/mbed/common/SerialBase.cpp index 93cbbb9fa4..926a910027 100644 --- a/libraries/mbed/common/SerialBase.cpp +++ b/libraries/mbed/common/SerialBase.cpp @@ -94,6 +94,7 @@ void SerialBase::set_flow_control(Flow type, PinName flow1, PinName flow2) { break; case RTSCTS: + case Disabled: serial_set_flow_control(&_serial, flow_type, flow1, flow2); break; From feacef8f3aee56b7401afbf3e3bf241ae0f1cb41 Mon Sep 17 00:00:00 2001 From: Joey Ye Date: Fri, 20 Dec 2013 15:08:20 +0800 Subject: [PATCH 22/33] Clean up GCC_ARM startup code --- .../TOOLCHAIN_GCC_ARM/startup_MKL25Z4.s | 73 +++---- .../TOOLCHAIN_GCC_ARM/startup_MKL46Z4.s | 81 ++++---- .../TOOLCHAIN_GCC_ARM/startup_LPC11xx.s | 63 +++--- .../TOOLCHAIN_GCC_ARM/startup_LPC11xx.s | 63 +++--- .../TOOLCHAIN_GCC_ARM/startup_LPC13xx.s | 70 ++++--- .../TOOLCHAIN_GCC_ARM/startup_LPC17xx.s | 86 ++++---- .../TOOLCHAIN_GCC_ARM/startup_LPC408x.s | 98 ++++----- .../TOOLCHAIN_GCC_ARM/startup_LPC43xx.s | 170 +++++++-------- .../TOOLCHAIN_GCC_ARM/startup_STM32F40x.s | 194 ++++++++---------- 9 files changed, 435 insertions(+), 463 deletions(-) diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_KL25Z/TOOLCHAIN_GCC_ARM/startup_MKL25Z4.s b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_KL25Z/TOOLCHAIN_GCC_ARM/startup_MKL25Z4.s index 02998d808f..d1a47ceafe 100644 --- a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_KL25Z/TOOLCHAIN_GCC_ARM/startup_MKL25Z4.s +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_KL25Z/TOOLCHAIN_GCC_ARM/startup_MKL25Z4.s @@ -150,16 +150,16 @@ Reset_Handler: ldr r3, =__data_end__ subs r3, r2 - ble .flash_to_ram_loop_end + ble .Lflash_to_ram_loop_end movs r4, 0 -.flash_to_ram_loop: +.Lflash_to_ram_loop: ldr r0, [r1,r4] str r0, [r2,r4] adds r4, 4 cmp r4, r3 - blt .flash_to_ram_loop -.flash_to_ram_loop_end: + blt .Lflash_to_ram_loop +.Lflash_to_ram_loop_end: ldr r0, =SystemInit blx r0 @@ -189,38 +189,41 @@ Reset_Handler: def_default_handler SysTick_Handler def_default_handler Default_Handler - def_default_handler DMA0_IRQHandler - def_default_handler DMA1_IRQHandler - def_default_handler DMA2_IRQHandler - def_default_handler DMA3_IRQHandler - def_default_handler FTFA_IRQHandler - def_default_handler LVD_LVW_IRQHandler - def_default_handler LLW_IRQHandler - def_default_handler I2C0_IRQHandler - def_default_handler I2C1_IRQHandler - def_default_handler SPI0_IRQHandler - def_default_handler SPI1_IRQHandler - def_default_handler UART0_IRQHandler - def_default_handler UART1_IRQHandler - def_default_handler UART2_IRQHandler - def_default_handler ADC0_IRQHandler - def_default_handler CMP0_IRQHandler - def_default_handler TPM0_IRQHandler - def_default_handler TPM1_IRQHandler - def_default_handler TPM2_IRQHandler - def_default_handler RTC_IRQHandler - def_default_handler RTC_Seconds_IRQHandler - def_default_handler PIT_IRQHandler - def_default_handler USB0_IRQHandler - def_default_handler DAC0_IRQHandler - def_default_handler TSI0_IRQHandler - def_default_handler MCG_IRQHandler - def_default_handler LPTimer_IRQHandler - def_default_handler PORTA_IRQHandler - def_default_handler PORTD_IRQHandler + .macro def_irq_default_handler handler_name + .weak \handler_name + .set \handler_name, Default_Handler + .endm - .weak DEF_IRQHandler - .set DEF_IRQHandler, Default_Handler + 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 FTFA_IRQHandler + def_irq_default_handler LVD_LVW_IRQHandler + def_irq_default_handler LLW_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 UART0_IRQHandler + def_irq_default_handler UART1_IRQHandler + def_irq_default_handler UART2_IRQHandler + def_irq_default_handler ADC0_IRQHandler + def_irq_default_handler CMP0_IRQHandler + def_irq_default_handler TPM0_IRQHandler + def_irq_default_handler TPM1_IRQHandler + def_irq_default_handler TPM2_IRQHandler + def_irq_default_handler RTC_IRQHandler + def_irq_default_handler RTC_Seconds_IRQHandler + def_irq_default_handler PIT_IRQHandler + def_irq_default_handler USB0_IRQHandler + def_irq_default_handler DAC0_IRQHandler + def_irq_default_handler TSI0_IRQHandler + def_irq_default_handler MCG_IRQHandler + def_irq_default_handler LPTimer_IRQHandler + def_irq_default_handler PORTA_IRQHandler + def_irq_default_handler PORTD_IRQHandler + def_irq_default_handler DEF_IRQHandler /* Flash protection region, placed at 0x400 */ .text diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_KL46Z/TOOLCHAIN_GCC_ARM/startup_MKL46Z4.s b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_KL46Z/TOOLCHAIN_GCC_ARM/startup_MKL46Z4.s index 6ddd57a586..9d297079d5 100644 --- a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_KL46Z/TOOLCHAIN_GCC_ARM/startup_MKL46Z4.s +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_KL46Z/TOOLCHAIN_GCC_ARM/startup_MKL46Z4.s @@ -150,16 +150,16 @@ Reset_Handler: ldr r3, =__data_end__ subs r3, r2 - ble .flash_to_ram_loop_end + ble .Lflash_to_ram_loop_end movs r4, 0 -.flash_to_ram_loop: +.Lflash_to_ram_loop: ldr r0, [r1,r4] str r0, [r2,r4] adds r4, 4 cmp r4, r3 - blt .flash_to_ram_loop -.flash_to_ram_loop_end: + blt .Lflash_to_ram_loop +.Lflash_to_ram_loop_end: ldr r0, =SystemInit blx r0 @@ -187,44 +187,45 @@ Reset_Handler: def_default_handler SVC_Handler def_default_handler PendSV_Handler def_default_handler SysTick_Handler - def_default_handler Default_Handler + def_default_handler Default_Handler - def_default_handler DMA0_IRQHandler - def_default_handler DMA1_IRQHandler - def_default_handler DMA2_IRQHandler - def_default_handler DMA3_IRQHandler - def_default_handler FTFA_IRQHandler - def_default_handler LVD_LVW_IRQHandler - def_default_handler LLW_IRQHandler - def_default_handler I2C0_IRQHandler - def_default_handler I2C1_IRQHandler - def_default_handler SPI0_IRQHandler - def_default_handler SPI1_IRQHandler - def_default_handler UART0_IRQHandler - def_default_handler UART1_IRQHandler - def_default_handler UART2_IRQHandler - def_default_handler ADC0_IRQHandler - def_default_handler CMP0_IRQHandler - def_default_handler TPM0_IRQHandler - def_default_handler TPM1_IRQHandler - def_default_handler TPM2_IRQHandler - def_default_handler RTC_IRQHandler - def_default_handler RTC_Seconds_IRQHandler - def_default_handler PIT_IRQHandler - def_default_handler I2S_IRQHandler - def_default_handler USB0_IRQHandler - def_default_handler DAC0_IRQHandler - def_default_handler TSI0_IRQHandler - def_default_handler MCG_IRQHandler - def_default_handler LPTimer_IRQHandler - def_default_handler LCD_IRQHandler - def_default_handler PORTA_IRQHandler - def_default_handler PORTD_IRQHandler - + .macro def_irq_default_handler handler_name + .weak \handler_name + .set \handler_name, Default_Handler + .endm - - .weak DEF_IRQHandler - .set DEF_IRQHandler, Default_Handler + 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 FTFA_IRQHandler + def_irq_default_handler LVD_LVW_IRQHandler + def_irq_default_handler LLW_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 UART0_IRQHandler + def_irq_default_handler UART1_IRQHandler + def_irq_default_handler UART2_IRQHandler + def_irq_default_handler ADC0_IRQHandler + def_irq_default_handler CMP0_IRQHandler + def_irq_default_handler TPM0_IRQHandler + def_irq_default_handler TPM1_IRQHandler + def_irq_default_handler TPM2_IRQHandler + def_irq_default_handler RTC_IRQHandler + def_irq_default_handler RTC_Seconds_IRQHandler + def_irq_default_handler PIT_IRQHandler + def_irq_default_handler I2S_IRQHandler + def_irq_default_handler USB0_IRQHandler + def_irq_default_handler DAC0_IRQHandler + def_irq_default_handler TSI0_IRQHandler + def_irq_default_handler MCG_IRQHandler + def_irq_default_handler LPTimer_IRQHandler + def_irq_default_handler LCD_IRQHandler + def_irq_default_handler PORTA_IRQHandler + def_irq_default_handler PORTD_IRQHandler + def_irq_default_handler DEF_IRQHandler /* Flash protection region, placed at 0x400 */ .text diff --git a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11UXX/TOOLCHAIN_GCC_ARM/startup_LPC11xx.s b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11UXX/TOOLCHAIN_GCC_ARM/startup_LPC11xx.s index 3ffdd07e58..f5155aedfd 100644 --- a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11UXX/TOOLCHAIN_GCC_ARM/startup_LPC11xx.s +++ b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11UXX/TOOLCHAIN_GCC_ARM/startup_LPC11xx.s @@ -150,16 +150,16 @@ Reset_Handler: ldr r3, =__data_end__ subs r3, r2 - ble .flash_to_ram_loop_end + ble .Lflash_to_ram_loop_end movs r4, 0 -.flash_to_ram_loop: +.Lflash_to_ram_loop: ldr r0, [r1,r4] str r0, [r2,r4] adds r4, 4 cmp r4, r3 - blt .flash_to_ram_loop -.flash_to_ram_loop_end: + blt .Lflash_to_ram_loop +.Lflash_to_ram_loop_end: ldr r0, =SystemInit blx r0 @@ -181,33 +181,36 @@ Reset_Handler: b . .size \handler_name, . - \handler_name .endm - - def_default_handler NMI_Handler - def_default_handler HardFault_Handler - def_default_handler SVC_Handler - def_default_handler PendSV_Handler - def_default_handler SysTick_Handler - def_default_handler Default_Handler - - def_default_handler WAKEUP_IRQHandler - def_default_handler SSP1_IRQHandler - def_default_handler I2C_IRQHandler - def_default_handler TIMER16_0_IRQHandler - def_default_handler TIMER16_1_IRQHandler - def_default_handler TIMER32_0_IRQHandler - def_default_handler TIMER32_1_IRQHandler - def_default_handler SSP0_IRQHandler - def_default_handler UART_IRQHandler - def_default_handler ADC_IRQHandler - def_default_handler WDT_IRQHandler - def_default_handler BOD_IRQHandler - def_default_handler PIOINT3_IRQHandler - def_default_handler PIOINT2_IRQHandler - def_default_handler PIOINT1_IRQHandler - def_default_handler PIOINT0_IRQHandler - .weak DEF_IRQHandler - .set DEF_IRQHandler, Default_Handler + def_default_handler NMI_Handler + def_default_handler HardFault_Handler + def_default_handler SVC_Handler + def_default_handler PendSV_Handler + def_default_handler SysTick_Handler + def_default_handler Default_Handler + + .macro def_irq_default_handler handler_name + .weak \handler_name + .set \handler_name, Default_Handler + .endm + + def_irq_default_handler WAKEUP_IRQHandler + def_irq_default_handler SSP1_IRQHandler + def_irq_default_handler I2C_IRQHandler + def_irq_default_handler TIMER16_0_IRQHandler + def_irq_default_handler TIMER16_1_IRQHandler + def_irq_default_handler TIMER32_0_IRQHandler + def_irq_default_handler TIMER32_1_IRQHandler + def_irq_default_handler SSP0_IRQHandler + def_irq_default_handler UART_IRQHandler + def_irq_default_handler ADC_IRQHandler + def_irq_default_handler WDT_IRQHandler + def_irq_default_handler BOD_IRQHandler + def_irq_default_handler PIOINT3_IRQHandler + def_irq_default_handler PIOINT2_IRQHandler + def_irq_default_handler PIOINT1_IRQHandler + def_irq_default_handler PIOINT0_IRQHandler + def_irq_default_handler DEF_IRQHandler .end diff --git a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11XX_11CXX/TOOLCHAIN_GCC_ARM/startup_LPC11xx.s b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11XX_11CXX/TOOLCHAIN_GCC_ARM/startup_LPC11xx.s index 3ffdd07e58..f5155aedfd 100644 --- a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11XX_11CXX/TOOLCHAIN_GCC_ARM/startup_LPC11xx.s +++ b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11XX_11CXX/TOOLCHAIN_GCC_ARM/startup_LPC11xx.s @@ -150,16 +150,16 @@ Reset_Handler: ldr r3, =__data_end__ subs r3, r2 - ble .flash_to_ram_loop_end + ble .Lflash_to_ram_loop_end movs r4, 0 -.flash_to_ram_loop: +.Lflash_to_ram_loop: ldr r0, [r1,r4] str r0, [r2,r4] adds r4, 4 cmp r4, r3 - blt .flash_to_ram_loop -.flash_to_ram_loop_end: + blt .Lflash_to_ram_loop +.Lflash_to_ram_loop_end: ldr r0, =SystemInit blx r0 @@ -181,33 +181,36 @@ Reset_Handler: b . .size \handler_name, . - \handler_name .endm - - def_default_handler NMI_Handler - def_default_handler HardFault_Handler - def_default_handler SVC_Handler - def_default_handler PendSV_Handler - def_default_handler SysTick_Handler - def_default_handler Default_Handler - - def_default_handler WAKEUP_IRQHandler - def_default_handler SSP1_IRQHandler - def_default_handler I2C_IRQHandler - def_default_handler TIMER16_0_IRQHandler - def_default_handler TIMER16_1_IRQHandler - def_default_handler TIMER32_0_IRQHandler - def_default_handler TIMER32_1_IRQHandler - def_default_handler SSP0_IRQHandler - def_default_handler UART_IRQHandler - def_default_handler ADC_IRQHandler - def_default_handler WDT_IRQHandler - def_default_handler BOD_IRQHandler - def_default_handler PIOINT3_IRQHandler - def_default_handler PIOINT2_IRQHandler - def_default_handler PIOINT1_IRQHandler - def_default_handler PIOINT0_IRQHandler - .weak DEF_IRQHandler - .set DEF_IRQHandler, Default_Handler + def_default_handler NMI_Handler + def_default_handler HardFault_Handler + def_default_handler SVC_Handler + def_default_handler PendSV_Handler + def_default_handler SysTick_Handler + def_default_handler Default_Handler + + .macro def_irq_default_handler handler_name + .weak \handler_name + .set \handler_name, Default_Handler + .endm + + def_irq_default_handler WAKEUP_IRQHandler + def_irq_default_handler SSP1_IRQHandler + def_irq_default_handler I2C_IRQHandler + def_irq_default_handler TIMER16_0_IRQHandler + def_irq_default_handler TIMER16_1_IRQHandler + def_irq_default_handler TIMER32_0_IRQHandler + def_irq_default_handler TIMER32_1_IRQHandler + def_irq_default_handler SSP0_IRQHandler + def_irq_default_handler UART_IRQHandler + def_irq_default_handler ADC_IRQHandler + def_irq_default_handler WDT_IRQHandler + def_irq_default_handler BOD_IRQHandler + def_irq_default_handler PIOINT3_IRQHandler + def_irq_default_handler PIOINT2_IRQHandler + def_irq_default_handler PIOINT1_IRQHandler + def_irq_default_handler PIOINT0_IRQHandler + def_irq_default_handler DEF_IRQHandler .end diff --git a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC13XX/TOOLCHAIN_GCC_ARM/startup_LPC13xx.s b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC13XX/TOOLCHAIN_GCC_ARM/startup_LPC13xx.s index a0266ded9e..7d5f0e04da 100644 --- a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC13XX/TOOLCHAIN_GCC_ARM/startup_LPC13xx.s +++ b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC13XX/TOOLCHAIN_GCC_ARM/startup_LPC13xx.s @@ -135,12 +135,12 @@ Reset_Handler: ldr r2, =__data_start__ ldr r3, =__data_end__ -.flash_to_ram_loop: +.Lflash_to_ram_loop: cmp r2, r3 ittt lt ldrlt r0, [r1], #4 strlt r0, [r2], #4 - blt .flash_to_ram_loop + blt .Lflash_to_ram_loop ldr r0, =SystemInit blx r0 @@ -149,6 +149,7 @@ Reset_Handler: .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 */ @@ -161,7 +162,7 @@ Reset_Handler: b . .size \handler_name, . - \handler_name .endm - + def_default_handler NMI_Handler def_default_handler HardFault_Handler def_default_handler MemManage_Handler @@ -173,37 +174,40 @@ Reset_Handler: def_default_handler SysTick_Handler def_default_handler Default_Handler - def_default_handler PIN_INT0_Handler - def_default_handler PIN_INT1_Handler - def_default_handler PIN_INT2_Handler - def_default_handler PIN_INT3_Handler - def_default_handler PIN_INT4_Handler - def_default_handler PIN_INT5_Handler - def_default_handler PIN_INT6_Handler - def_default_handler PIN_INT7_Handler - def_default_handler GINT0_Handler - def_default_handler GINT1_Handler - def_default_handler OSTIMER_Handler - def_default_handler SSP1_Handler - def_default_handler I2C_Handler - def_default_handler CT16B0_Handler - def_default_handler CT16B1_Handler - def_default_handler CT32B0_Handler - def_default_handler CT32B1_Handler - def_default_handler SSP0_Handler - def_default_handler USART_Handler - def_default_handler USB_Handler - def_default_handler USB_FIQHandler - def_default_handler ADC_Handler - def_default_handler WDT_Handler - def_default_handler BOD_Handler - def_default_handler FMC_Handler - def_default_handler OSCFAIL_Handler - def_default_handler PVTCIRCUIT_Handler - def_default_handler USBWakeup_Handler + .macro def_irq_default_handler handler_name + .weak \handler_name + .set \handler_name, Default_Handler + .endm - .weak DEF_IRQHandler - .set DEF_IRQHandler, Default_Handler + def_irq_default_handler PIN_INT0_Handler + def_irq_default_handler PIN_INT1_Handler + def_irq_default_handler PIN_INT2_Handler + def_irq_default_handler PIN_INT3_Handler + def_irq_default_handler PIN_INT4_Handler + def_irq_default_handler PIN_INT5_Handler + def_irq_default_handler PIN_INT6_Handler + def_irq_default_handler PIN_INT7_Handler + def_irq_default_handler GINT0_Handler + def_irq_default_handler GINT1_Handler + def_irq_default_handler OSTIMER_Handler + def_irq_default_handler SSP1_Handler + def_irq_default_handler I2C_Handler + def_irq_default_handler CT16B0_Handler + def_irq_default_handler CT16B1_Handler + def_irq_default_handler CT32B0_Handler + def_irq_default_handler CT32B1_Handler + def_irq_default_handler SSP0_Handler + def_irq_default_handler USART_Handler + def_irq_default_handler USB_Handler + def_irq_default_handler USB_FIQHandler + def_irq_default_handler ADC_Handler + def_irq_default_handler WDT_Handler + def_irq_default_handler BOD_Handler + def_irq_default_handler FMC_Handler + def_irq_default_handler OSCFAIL_Handler + def_irq_default_handler PVTCIRCUIT_Handler + def_irq_default_handler USBWakeup_Handler + def_irq_default_handler DEF_IRQHandler .end diff --git a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC176X/TOOLCHAIN_GCC_ARM/startup_LPC17xx.s b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC176X/TOOLCHAIN_GCC_ARM/startup_LPC17xx.s index b4b3dee4ee..4a8e973a33 100644 --- a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC176X/TOOLCHAIN_GCC_ARM/startup_LPC17xx.s +++ b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC176X/TOOLCHAIN_GCC_ARM/startup_LPC17xx.s @@ -138,12 +138,12 @@ Reset_Handler: ldr r2, =__data_start__ ldr r3, =__data_end__ -.flash_to_ram_loop: +.Lflash_to_ram_loop: cmp r2, r3 ittt lt ldrlt r0, [r1], #4 strlt r0, [r2], #4 - blt .flash_to_ram_loop + blt .Lflash_to_ram_loop ldr r0, =SystemInit blx r0 @@ -152,6 +152,7 @@ Reset_Handler: .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 */ @@ -164,7 +165,7 @@ Reset_Handler: b . .size \handler_name, . - \handler_name .endm - + def_default_handler NMI_Handler def_default_handler HardFault_Handler def_default_handler MemManage_Handler @@ -175,45 +176,48 @@ Reset_Handler: def_default_handler PendSV_Handler def_default_handler SysTick_Handler def_default_handler Default_Handler - - def_default_handler WDT_IRQHandler - def_default_handler TIMER0_IRQHandler - def_default_handler TIMER1_IRQHandler - def_default_handler TIMER2_IRQHandler - def_default_handler TIMER3_IRQHandler - def_default_handler UART0_IRQHandler - def_default_handler UART1_IRQHandler - def_default_handler UART2_IRQHandler - def_default_handler UART3_IRQHandler - def_default_handler PWM1_IRQHandler - def_default_handler I2C0_IRQHandler - def_default_handler I2C1_IRQHandler - def_default_handler I2C2_IRQHandler - def_default_handler SPI_IRQHandler - def_default_handler SSP0_IRQHandler - def_default_handler SSP1_IRQHandler - def_default_handler PLL0_IRQHandler - def_default_handler RTC_IRQHandler - def_default_handler EINT0_IRQHandler - def_default_handler EINT1_IRQHandler - def_default_handler EINT2_IRQHandler - def_default_handler EINT3_IRQHandler - def_default_handler ADC_IRQHandler - def_default_handler BOD_IRQHandler - def_default_handler USB_IRQHandler - def_default_handler CAN_IRQHandler - def_default_handler DMA_IRQHandler - def_default_handler I2S_IRQHandler - def_default_handler ENET_IRQHandler - def_default_handler RIT_IRQHandler - def_default_handler MCPWM_IRQHandler - def_default_handler QEI_IRQHandler - def_default_handler PLL1_IRQHandler - def_default_handler USBActivity_IRQHandler - def_default_handler CANActivity_IRQHandler - .weak DEF_IRQHandler - .set DEF_IRQHandler, Default_Handler + .macro def_irq_default_handler handler_name + .weak \handler_name + .set \handler_name, Default_Handler + .endm + + def_irq_default_handler WDT_IRQHandler + def_irq_default_handler TIMER0_IRQHandler + def_irq_default_handler TIMER1_IRQHandler + def_irq_default_handler TIMER2_IRQHandler + def_irq_default_handler TIMER3_IRQHandler + def_irq_default_handler UART0_IRQHandler + def_irq_default_handler UART1_IRQHandler + def_irq_default_handler UART2_IRQHandler + def_irq_default_handler UART3_IRQHandler + def_irq_default_handler PWM1_IRQHandler + def_irq_default_handler I2C0_IRQHandler + def_irq_default_handler I2C1_IRQHandler + def_irq_default_handler I2C2_IRQHandler + def_irq_default_handler SPI_IRQHandler + def_irq_default_handler SSP0_IRQHandler + def_irq_default_handler SSP1_IRQHandler + def_irq_default_handler PLL0_IRQHandler + def_irq_default_handler RTC_IRQHandler + def_irq_default_handler EINT0_IRQHandler + def_irq_default_handler EINT1_IRQHandler + def_irq_default_handler EINT2_IRQHandler + def_irq_default_handler EINT3_IRQHandler + def_irq_default_handler ADC_IRQHandler + def_irq_default_handler BOD_IRQHandler + def_irq_default_handler USB_IRQHandler + def_irq_default_handler CAN_IRQHandler + def_irq_default_handler DMA_IRQHandler + def_irq_default_handler I2S_IRQHandler + def_irq_default_handler ENET_IRQHandler + def_irq_default_handler RIT_IRQHandler + def_irq_default_handler MCPWM_IRQHandler + def_irq_default_handler QEI_IRQHandler + def_irq_default_handler PLL1_IRQHandler + def_irq_default_handler USBActivity_IRQHandler + def_irq_default_handler CANActivity_IRQHandler + def_irq_default_handler DEF_IRQHandler .end diff --git a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_ARM/startup_LPC408x.s b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_ARM/startup_LPC408x.s index 83a7583570..0377b2ba53 100644 --- a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_ARM/startup_LPC408x.s +++ b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_ARM/startup_LPC408x.s @@ -144,12 +144,12 @@ Reset_Handler: ldr r2, =__data_start__ ldr r3, =__data_end__ -.flash_to_ram_loop: +.Lflash_to_ram_loop: cmp r2, r3 ittt lt ldrlt r0, [r1], #4 strlt r0, [r2], #4 - blt .flash_to_ram_loop + blt .Lflash_to_ram_loop ldr r0, =SystemInit blx r0 @@ -158,6 +158,7 @@ Reset_Handler: .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 */ @@ -170,7 +171,7 @@ Reset_Handler: b . .size \handler_name, . - \handler_name .endm - + def_default_handler NMI_Handler def_default_handler HardFault_Handler def_default_handler MemManage_Handler @@ -181,51 +182,54 @@ Reset_Handler: def_default_handler PendSV_Handler def_default_handler SysTick_Handler def_default_handler Default_Handler - - def_default_handler WDT_IRQHandler - def_default_handler TIMER0_IRQHandler - def_default_handler TIMER1_IRQHandler - def_default_handler TIMER2_IRQHandler - def_default_handler TIMER3_IRQHandler - def_default_handler UART0_IRQHandler - def_default_handler UART1_IRQHandler - def_default_handler UART2_IRQHandler - def_default_handler UART3_IRQHandler - def_default_handler PWM1_IRQHandler - def_default_handler I2C0_IRQHandler - def_default_handler I2C1_IRQHandler - def_default_handler I2C2_IRQHandler -/* def_default_handler SPI_IRQHandler */ - def_default_handler SSP0_IRQHandler - def_default_handler SSP1_IRQHandler - def_default_handler PLL0_IRQHandler - def_default_handler RTC_IRQHandler - def_default_handler EINT0_IRQHandler - def_default_handler EINT1_IRQHandler - def_default_handler EINT2_IRQHandler - def_default_handler EINT3_IRQHandler - def_default_handler ADC_IRQHandler - def_default_handler BOD_IRQHandler - def_default_handler USB_IRQHandler - def_default_handler CAN_IRQHandler - def_default_handler DMA_IRQHandler - def_default_handler I2S_IRQHandler - def_default_handler ENET_IRQHandler - def_default_handler MCI_IRQHandler - def_default_handler MCPWM_IRQHandler - def_default_handler QEI_IRQHandler - def_default_handler PLL1_IRQHandler - def_default_handler USBActivity_IRQHandler - def_default_handler CANActivity_IRQHandler - def_default_handler UART4_IRQHandler - def_default_handler SSP2_IRQHandler - def_default_handler LCD_IRQHandler - def_default_handler GPIO_IRQHandler - def_default_handler PWM0_IRQHandler - def_default_handler EEPROM_IRQHandler - .weak DEF_IRQHandler - .set DEF_IRQHandler, Default_Handler + .macro def_irq_default_handler handler_name + .weak \handler_name + .set \handler_name, Default_Handler + .endm + + def_irq_default_handler WDT_IRQHandler + def_irq_default_handler TIMER0_IRQHandler + def_irq_default_handler TIMER1_IRQHandler + def_irq_default_handler TIMER2_IRQHandler + def_irq_default_handler TIMER3_IRQHandler + def_irq_default_handler UART0_IRQHandler + def_irq_default_handler UART1_IRQHandler + def_irq_default_handler UART2_IRQHandler + def_irq_default_handler UART3_IRQHandler + def_irq_default_handler PWM1_IRQHandler + def_irq_default_handler I2C0_IRQHandler + def_irq_default_handler I2C1_IRQHandler + def_irq_default_handler I2C2_IRQHandler +/* def_irq_default_handler SPI_IRQHandler */ + def_irq_default_handler SSP0_IRQHandler + def_irq_default_handler SSP1_IRQHandler + def_irq_default_handler PLL0_IRQHandler + def_irq_default_handler RTC_IRQHandler + def_irq_default_handler EINT0_IRQHandler + def_irq_default_handler EINT1_IRQHandler + def_irq_default_handler EINT2_IRQHandler + def_irq_default_handler EINT3_IRQHandler + def_irq_default_handler ADC_IRQHandler + def_irq_default_handler BOD_IRQHandler + def_irq_default_handler USB_IRQHandler + def_irq_default_handler CAN_IRQHandler + def_irq_default_handler DMA_IRQHandler + def_irq_default_handler I2S_IRQHandler + def_irq_default_handler ENET_IRQHandler + def_irq_default_handler MCI_IRQHandler + def_irq_default_handler MCPWM_IRQHandler + def_irq_default_handler QEI_IRQHandler + def_irq_default_handler PLL1_IRQHandler + def_irq_default_handler USBActivity_IRQHandler + def_irq_default_handler CANActivity_IRQHandler + def_irq_default_handler UART4_IRQHandler + def_irq_default_handler SSP2_IRQHandler + def_irq_default_handler LCD_IRQHandler + def_irq_default_handler GPIO_IRQHandler + def_irq_default_handler PWM0_IRQHandler + def_irq_default_handler EEPROM_IRQHandler + def_irq_default_handler DEF_IRQHandler .end diff --git a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC43XX/TOOLCHAIN_GCC_ARM/startup_LPC43xx.s b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC43XX/TOOLCHAIN_GCC_ARM/startup_LPC43xx.s index 851b116334..f137dc05bd 100644 --- a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC43XX/TOOLCHAIN_GCC_ARM/startup_LPC43xx.s +++ b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC43XX/TOOLCHAIN_GCC_ARM/startup_LPC43xx.s @@ -164,62 +164,25 @@ Reset_Handler: ldr r2, =__data_start__ ldr r3, =__data_end__ -.if 1 -/* Here are two copies of loop implemenations. First one favors code size - * and the second one favors performance. Default uses the first one. - * Change to "#if 0" to use the second one */ .LC0: cmp r2, r3 ittt lt ldrlt r0, [r1], #4 strlt r0, [r2], #4 blt .LC0 -.else - subs r3, r2 - ble .LC1 -.LC0: - subs r3, #4 - ldr r0, [r1, r3] - str r0, [r2, r3] - bgt .LC0 -.LC1: -.endif -.ifdef __STARTUP_CLEAR_BSS -/* This part of work usually is done in C library startup code. Otherwise, - * define this macro to enable it in this startup. - * - * Loop to zero out BSS section, which uses following symbols - * in linker script: - * __bss_start__: start of BSS section. Must align to 4 - * __bss_end__: end of BSS section. Must align to 4 - */ - ldr r1, =__bss_start__ - ldr r2, =__bss_end__ - - movs r0, 0 -.LC2: - cmp r1, r2 - itt lt - strlt r0, [r1], #4 - blt .LC2 -.endif /* __STARTUP_CLEAR_BSS */ - -.ifndef __NO_SYSTEM_INIT - bl SystemInit -.endif - -.ifndef __START -.set __START,_start -.endif - bl __START + 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_irq_handler handler_name + .macro def_default_handler handler_name .align 1 .thumb_func .weak \handler_name @@ -229,64 +192,69 @@ Reset_Handler: .size \handler_name, . - \handler_name .endm - def_irq_handler NMI_Handler - def_irq_handler HardFault_Handler - def_irq_handler MemManage_Handler - def_irq_handler BusFault_Handler - def_irq_handler UsageFault_Handler - def_irq_handler SVC_Handler - def_irq_handler DebugMon_Handler - def_irq_handler PendSV_Handler - def_irq_handler SysTick_Handler - def_irq_handler Default_Handler + 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 - def_irq_handler DAC_IRQHandler - def_irq_handler M0CORE_IRQHandler - def_irq_handler DMA_IRQHandler - def_irq_handler FLASHEEPROM_IRQHandler - def_irq_handler ETHERNET_IRQHandler - def_irq_handler SDIO_IRQHandler - def_irq_handler LCD_IRQHandler - def_irq_handler USB0_IRQHandler - def_irq_handler USB1_IRQHandler - def_irq_handler SCT_IRQHandler - def_irq_handler RITIMER_IRQHandler - def_irq_handler TIMER0_IRQHandler - def_irq_handler TIMER1_IRQHandler - def_irq_handler TIMER2_IRQHandler - def_irq_handler TIMER3_IRQHandler - def_irq_handler MCPWM_IRQHandler - def_irq_handler ADC0_IRQHandler - def_irq_handler I2C0_IRQHandler - def_irq_handler I2C1_IRQHandler - def_irq_handler SPI_IRQHandler - def_irq_handler ADC1_IRQHandler - def_irq_handler SSP0_IRQHandler - def_irq_handler SSP1_IRQHandler - def_irq_handler USART0_IRQHandler - def_irq_handler UART1_IRQHandler - def_irq_handler USART2_IRQHandler - def_irq_handler USART3_IRQHandler - def_irq_handler I2S0_IRQHandler - def_irq_handler I2S1_IRQHandler - def_irq_handler SPIFI_IRQHandler - def_irq_handler SGPIO_IRQHandler - def_irq_handler PIN_INT0_IRQHandler - def_irq_handler PIN_INT1_IRQHandler - def_irq_handler PIN_INT2_IRQHandler - def_irq_handler PIN_INT3_IRQHandler - def_irq_handler PIN_INT4_IRQHandler - def_irq_handler PIN_INT5_IRQHandler - def_irq_handler PIN_INT6_IRQHandler - def_irq_handler PIN_INT7_IRQHandler - def_irq_handler GINT0_IRQHandler - def_irq_handler GINT1_IRQHandler - def_irq_handler EVENTROUTER_IRQHandler - def_irq_handler C_CAN1_IRQHandler - def_irq_handler ATIMER_IRQHandler - def_irq_handler RTC_IRQHandler - def_irq_handler WWDT_IRQHandler - def_irq_handler C_CAN0_IRQHandler - def_irq_handler QEI_IRQHandler + .macro def_irq_default_handler handler_name + .weak \handler_name + .set \handler_name, Default_Handler + .endm + + def_irq_default_handler DAC_IRQHandler + def_irq_default_handler M0CORE_IRQHandler + def_irq_default_handler DMA_IRQHandler + def_irq_default_handler FLASHEEPROM_IRQHandler + def_irq_default_handler ETHERNET_IRQHandler + def_irq_default_handler SDIO_IRQHandler + def_irq_default_handler LCD_IRQHandler + def_irq_default_handler USB0_IRQHandler + def_irq_default_handler USB1_IRQHandler + def_irq_default_handler SCT_IRQHandler + def_irq_default_handler RITIMER_IRQHandler + def_irq_default_handler TIMER0_IRQHandler + def_irq_default_handler TIMER1_IRQHandler + def_irq_default_handler TIMER2_IRQHandler + def_irq_default_handler TIMER3_IRQHandler + def_irq_default_handler MCPWM_IRQHandler + def_irq_default_handler ADC0_IRQHandler + def_irq_default_handler I2C0_IRQHandler + def_irq_default_handler I2C1_IRQHandler + def_irq_default_handler SPI_IRQHandler + def_irq_default_handler ADC1_IRQHandler + def_irq_default_handler SSP0_IRQHandler + def_irq_default_handler SSP1_IRQHandler + def_irq_default_handler USART0_IRQHandler + def_irq_default_handler UART1_IRQHandler + def_irq_default_handler USART2_IRQHandler + def_irq_default_handler USART3_IRQHandler + def_irq_default_handler I2S0_IRQHandler + def_irq_default_handler I2S1_IRQHandler + def_irq_default_handler SPIFI_IRQHandler + def_irq_default_handler SGPIO_IRQHandler + def_irq_default_handler PIN_INT0_IRQHandler + def_irq_default_handler PIN_INT1_IRQHandler + def_irq_default_handler PIN_INT2_IRQHandler + def_irq_default_handler PIN_INT3_IRQHandler + def_irq_default_handler PIN_INT4_IRQHandler + def_irq_default_handler PIN_INT5_IRQHandler + def_irq_default_handler PIN_INT6_IRQHandler + def_irq_default_handler PIN_INT7_IRQHandler + def_irq_default_handler GINT0_IRQHandler + def_irq_default_handler GINT1_IRQHandler + def_irq_default_handler EVENTROUTER_IRQHandler + def_irq_default_handler C_CAN1_IRQHandler + def_irq_default_handler ATIMER_IRQHandler + def_irq_default_handler RTC_IRQHandler + def_irq_default_handler WWDT_IRQHandler + def_irq_default_handler C_CAN0_IRQHandler + def_irq_default_handler QEI_IRQHandler .end diff --git a/libraries/mbed/targets/cmsis/TARGET_STM/TARGET_STM32F4XX/TOOLCHAIN_GCC_ARM/startup_STM32F40x.s b/libraries/mbed/targets/cmsis/TARGET_STM/TARGET_STM32F4XX/TOOLCHAIN_GCC_ARM/startup_STM32F40x.s index e6e6fcc5a1..2c55e30c04 100644 --- a/libraries/mbed/targets/cmsis/TARGET_STM/TARGET_STM32F4XX/TOOLCHAIN_GCC_ARM/startup_STM32F40x.s +++ b/libraries/mbed/targets/cmsis/TARGET_STM/TARGET_STM32F4XX/TOOLCHAIN_GCC_ARM/startup_STM32F40x.s @@ -196,27 +196,6 @@ Reset_Handler: strlt r0, [r2], #4 blt .LC0 -/* This part of work usually is done in C library startup code. Otherwise, - * define this macro to enable it in this startup. - * - * Loop to zero out BSS section, which uses following symbols - * in linker script: - * __bss_start__: start of BSS section. Must align to 4 - * __bss_end__: end of BSS section. Must align to 4 - * - * Question - Why is this not in the mbed version? - */ - ldr r1, =__bss_start__ - ldr r2, =__bss_end__ - - movs r0, 0 -.LC2: - cmp r1, r2 - itt lt - strlt r0, [r1], #4 - blt .LC2 -# End clearing the BSS section - ldr r0, =SystemInit blx r0 ldr r0, =_start @@ -224,6 +203,7 @@ Reset_Handler: .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 */ @@ -248,91 +228,93 @@ Reset_Handler: def_default_handler SysTick_Handler def_default_handler Default_Handler - def_default_handler WWDG_IRQHandler - def_default_handler PVD_IRQHandler - def_default_handler TAMP_STAMP_IRQHandler - def_default_handler RTC_WKUP_IRQHandler - def_default_handler FLASH_IRQHandler - def_default_handler RCC_IRQHandler - def_default_handler EXTI0_IRQHandler - def_default_handler EXTI1_IRQHandler - def_default_handler EXTI2_IRQHandler - def_default_handler EXTI3_IRQHandler - def_default_handler EXTI4_IRQHandler - def_default_handler DMA1_Stream0_IRQHandler - def_default_handler DMA1_Stream1_IRQHandler - def_default_handler DMA1_Stream2_IRQHandler - def_default_handler DMA1_Stream3_IRQHandler - def_default_handler DMA1_Stream4_IRQHandler - def_default_handler DMA1_Stream5_IRQHandler - def_default_handler DMA1_Stream6_IRQHandler - def_default_handler ADC_IRQHandler - def_default_handler CAN1_TX_IRQHandler - def_default_handler CAN1_RX0_IRQHandler - def_default_handler CAN1_RX1_IRQHandler - def_default_handler CAN1_SCE_IRQHandler - def_default_handler EXTI9_5_IRQHandler - def_default_handler TIM1_BRK_TIM9_IRQHandler - def_default_handler TIM1_UP_TIM10_IRQHandler - def_default_handler TIM1_TRG_COM_TIM11_IRQHandler - def_default_handler TIM1_CC_IRQHandler - def_default_handler TIM2_IRQHandler - def_default_handler TIM3_IRQHandler - def_default_handler TIM4_IRQHandler - def_default_handler I2C1_EV_IRQHandler - def_default_handler I2C1_ER_IRQHandler - def_default_handler I2C2_EV_IRQHandler - def_default_handler I2C2_ER_IRQHandler - def_default_handler SPI1_IRQHandler - def_default_handler SPI2_IRQHandler - def_default_handler USART1_IRQHandler - def_default_handler USART2_IRQHandler - def_default_handler USART3_IRQHandler - def_default_handler EXTI15_10_IRQHandler - def_default_handler RTC_Alarm_IRQHandler - def_default_handler OTG_FS_WKUP_IRQHandler - def_default_handler TIM8_BRK_TIM12_IRQHandler - def_default_handler TIM8_UP_TIM13_IRQHandler - def_default_handler TIM8_TRG_COM_TIM14_IRQHandler - def_default_handler TIM8_CC_IRQHandler - def_default_handler DMA1_Stream7_IRQHandler - def_default_handler FSMC_IRQHandler - def_default_handler SDIO_IRQHandler - def_default_handler TIM5_IRQHandler - def_default_handler SPI3_IRQHandler - def_default_handler UART4_IRQHandler - def_default_handler UART5_IRQHandler - def_default_handler TIM6_DAC_IRQHandler - def_default_handler TIM7_IRQHandler - def_default_handler DMA2_Stream0_IRQHandler - def_default_handler DMA2_Stream1_IRQHandler - def_default_handler DMA2_Stream2_IRQHandler - def_default_handler DMA2_Stream3_IRQHandler - def_default_handler DMA2_Stream4_IRQHandler - def_default_handler ETH_IRQHandler - def_default_handler ETH_WKUP_IRQHandler - def_default_handler CAN2_TX_IRQHandler - def_default_handler CAN2_RX0_IRQHandler - def_default_handler CAN2_RX1_IRQHandler - def_default_handler CAN2_SCE_IRQHandler - def_default_handler OTG_FS_IRQHandler - def_default_handler DMA2_Stream5_IRQHandler - def_default_handler DMA2_Stream6_IRQHandler - def_default_handler DMA2_Stream7_IRQHandler - def_default_handler USART6_IRQHandler - def_default_handler I2C3_EV_IRQHandler - def_default_handler I2C3_ER_IRQHandler - def_default_handler OTG_HS_EP1_OUT_IRQHandler - def_default_handler OTG_HS_EP1_IN_IRQHandler - def_default_handler OTG_HS_WKUP_IRQHandler - def_default_handler OTG_HS_IRQHandler - def_default_handler DCMI_IRQHandler - def_default_handler CRYP_IRQHandler - def_default_handler HASH_RNG_IRQHandler - def_default_handler FPU_IRQHandler + .macro def_irq_default_handler handler_name + .weak \handler_name + .set \handler_name, Default_Handler + .endm - - .weak DEF_IRQHandler - .set DEF_IRQHandler, Default_Handler + def_irq_default_handler WWDG_IRQHandler + def_irq_default_handler PVD_IRQHandler + def_irq_default_handler TAMP_STAMP_IRQHandler + def_irq_default_handler RTC_WKUP_IRQHandler + def_irq_default_handler FLASH_IRQHandler + def_irq_default_handler RCC_IRQHandler + def_irq_default_handler EXTI0_IRQHandler + def_irq_default_handler EXTI1_IRQHandler + def_irq_default_handler EXTI2_IRQHandler + def_irq_default_handler EXTI3_IRQHandler + def_irq_default_handler EXTI4_IRQHandler + def_irq_default_handler DMA1_Stream0_IRQHandler + def_irq_default_handler DMA1_Stream1_IRQHandler + def_irq_default_handler DMA1_Stream2_IRQHandler + def_irq_default_handler DMA1_Stream3_IRQHandler + def_irq_default_handler DMA1_Stream4_IRQHandler + def_irq_default_handler DMA1_Stream5_IRQHandler + def_irq_default_handler DMA1_Stream6_IRQHandler + def_irq_default_handler ADC_IRQHandler + def_irq_default_handler CAN1_TX_IRQHandler + def_irq_default_handler CAN1_RX0_IRQHandler + def_irq_default_handler CAN1_RX1_IRQHandler + def_irq_default_handler CAN1_SCE_IRQHandler + def_irq_default_handler EXTI9_5_IRQHandler + def_irq_default_handler TIM1_BRK_TIM9_IRQHandler + def_irq_default_handler TIM1_UP_TIM10_IRQHandler + def_irq_default_handler TIM1_TRG_COM_TIM11_IRQHandler + def_irq_default_handler TIM1_CC_IRQHandler + def_irq_default_handler TIM2_IRQHandler + def_irq_default_handler TIM3_IRQHandler + def_irq_default_handler TIM4_IRQHandler + def_irq_default_handler I2C1_EV_IRQHandler + def_irq_default_handler I2C1_ER_IRQHandler + def_irq_default_handler I2C2_EV_IRQHandler + def_irq_default_handler I2C2_ER_IRQHandler + def_irq_default_handler SPI1_IRQHandler + def_irq_default_handler SPI2_IRQHandler + def_irq_default_handler USART1_IRQHandler + def_irq_default_handler USART2_IRQHandler + def_irq_default_handler USART3_IRQHandler + def_irq_default_handler EXTI15_10_IRQHandler + def_irq_default_handler RTC_Alarm_IRQHandler + def_irq_default_handler OTG_FS_WKUP_IRQHandler + def_irq_default_handler TIM8_BRK_TIM12_IRQHandler + def_irq_default_handler TIM8_UP_TIM13_IRQHandler + def_irq_default_handler TIM8_TRG_COM_TIM14_IRQHandler + def_irq_default_handler TIM8_CC_IRQHandler + def_irq_default_handler DMA1_Stream7_IRQHandler + def_irq_default_handler FSMC_IRQHandler + def_irq_default_handler SDIO_IRQHandler + def_irq_default_handler TIM5_IRQHandler + def_irq_default_handler SPI3_IRQHandler + def_irq_default_handler UART4_IRQHandler + def_irq_default_handler UART5_IRQHandler + def_irq_default_handler TIM6_DAC_IRQHandler + def_irq_default_handler TIM7_IRQHandler + def_irq_default_handler DMA2_Stream0_IRQHandler + def_irq_default_handler DMA2_Stream1_IRQHandler + def_irq_default_handler DMA2_Stream2_IRQHandler + def_irq_default_handler DMA2_Stream3_IRQHandler + def_irq_default_handler DMA2_Stream4_IRQHandler + def_irq_default_handler ETH_IRQHandler + def_irq_default_handler ETH_WKUP_IRQHandler + def_irq_default_handler CAN2_TX_IRQHandler + def_irq_default_handler CAN2_RX0_IRQHandler + def_irq_default_handler CAN2_RX1_IRQHandler + def_irq_default_handler CAN2_SCE_IRQHandler + def_irq_default_handler OTG_FS_IRQHandler + def_irq_default_handler DMA2_Stream5_IRQHandler + def_irq_default_handler DMA2_Stream6_IRQHandler + def_irq_default_handler DMA2_Stream7_IRQHandler + def_irq_default_handler USART6_IRQHandler + def_irq_default_handler I2C3_EV_IRQHandler + def_irq_default_handler I2C3_ER_IRQHandler + def_irq_default_handler OTG_HS_EP1_OUT_IRQHandler + def_irq_default_handler OTG_HS_EP1_IN_IRQHandler + def_irq_default_handler OTG_HS_WKUP_IRQHandler + def_irq_default_handler OTG_HS_IRQHandler + def_irq_default_handler DCMI_IRQHandler + def_irq_default_handler CRYP_IRQHandler + def_irq_default_handler HASH_RNG_IRQHandler + def_irq_default_handler FPU_IRQHandler + def_irq_default_handler DEF_IRQHandler .end From 366221524a0466aa4c5acffa35aa54bcfbf1bb0e Mon Sep 17 00:00:00 2001 From: 0xc0170 Date: Mon, 23 Dec 2013 19:57:10 +0100 Subject: [PATCH 23/33] SPI, RTC, Serial changes - SPI - implementation - RTC - there's 32.768kHz crystal, use that as a source - Serial - 10bit transfer --- .../TARGET_K20D5M/analogin_api.c | 2 +- .../TARGET_Freescale/TARGET_K20D5M/gpio_api.c | 19 ++- .../TARGET_K20D5M/gpio_irq_api.c | 22 +++- .../TARGET_Freescale/TARGET_K20D5M/rtc_api.c | 16 +-- .../TARGET_K20D5M/serial_api.c | 124 +++++++++--------- .../TARGET_Freescale/TARGET_K20D5M/spi_api.c | 71 +++++----- .../TARGET_K20D5M/us_ticker.c | 27 ++-- 7 files changed, 148 insertions(+), 133 deletions(-) diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/analogin_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/analogin_api.c index 386384abcd..354c055962 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/analogin_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/analogin_api.c @@ -52,7 +52,7 @@ void analogin_init(analogin_t *obj, PinName pin) { | ADC_CFG1_MODE(3) // (16)bits Resolution | ADC_CFG1_ADICLK(1); // Input Clock: (Bus Clock)/2 - ADC0->CFG2 = ADC_CFG2_MUXSEL_MASK // ADxxb or ADxxa channels + ADC0->CFG2 = ADC_CFG2_MUXSEL_MASK // ADxxb or ADxxa channels | ADC_CFG2_ADACKEN_MASK // Asynchronous Clock Output Enable | ADC_CFG2_ADHSC_MASK // High-Speed Configuration | ADC_CFG2_ADLSTS(0); // Long Sample Time Select diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_api.c index d039c57a05..acfbcbdc4d 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_api.c @@ -22,7 +22,8 @@ uint32_t gpio_set(PinName pin) { } void gpio_init(gpio_t *obj, PinName pin, PinDirection direction) { - if(pin == NC) return; + if(pin == NC) + return; obj->pin = pin; obj->mask = gpio_set(pin); @@ -37,8 +38,12 @@ void gpio_init(gpio_t *obj, PinName pin, PinDirection direction) { gpio_dir(obj, direction); switch (direction) { - case PIN_OUTPUT: pin_mode(pin, PullNone); break; - case PIN_INPUT : pin_mode(pin, PullUp); break; + case PIN_OUTPUT: + pin_mode(pin, PullNone); + break; + case PIN_INPUT : + pin_mode(pin, PullUp); + break; } } @@ -48,7 +53,11 @@ void gpio_mode(gpio_t *obj, PinMode mode) { void gpio_dir(gpio_t *obj, PinDirection direction) { switch (direction) { - case PIN_INPUT : *obj->reg_dir &= ~obj->mask; break; - case PIN_OUTPUT: *obj->reg_dir |= obj->mask; break; + case PIN_INPUT : + *obj->reg_dir &= ~obj->mask; + break; + case PIN_OUTPUT: + *obj->reg_dir |= obj->mask; + break; } } diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_irq_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_irq_api.c index 16245bbde4..e71d70c870 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_irq_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_irq_api.c @@ -53,7 +53,6 @@ static void handle_interrupt_in(PORT_Type *port, int ch_base) { case IRQ_EITHER_EDGE: gpio += (port_num * 0x40); - //gpio = (port == PORTA) ? (PTA) : (PTD); event = (gpio->PDIR & pmask) ? (IRQ_RISE) : (IRQ_FALL); break; } @@ -82,23 +81,32 @@ int gpio_irq_init(gpio_irq_t *obj, PinName pin, gpio_irq_handler handler, uint32 IRQn_Type irq_n; switch (obj->port) { case PortA: - ch_base = 0; irq_n = PORTA_IRQn; vector = (uint32_t)gpio_irqA; + ch_base = 0; + irq_n = PORTA_IRQn; + vector = (uint32_t)gpio_irqA; break; case PortB: - ch_base = 0; irq_n = PORTB_IRQn; vector = (uint32_t)gpio_irqB; + ch_base = 32; + irq_n = PORTB_IRQn; + vector = (uint32_t)gpio_irqB; break; case PortC: - ch_base = 0; irq_n = PORTC_IRQn; vector = (uint32_t)gpio_irqC; + ch_base = 64; + irq_n = PORTC_IRQn; + vector = (uint32_t)gpio_irqC; break; case PortD: - ch_base = 32; irq_n = PORTD_IRQn; vector = (uint32_t)gpio_irqD; + ch_base = 96; + irq_n = PORTD_IRQn; vector = (uint32_t)gpio_irqD; break; case PortE: - ch_base = 0; irq_n = PORTE_IRQn; vector = (uint32_t)gpio_irqE; + ch_base = 128; + irq_n = PORTE_IRQn; + vector = (uint32_t)gpio_irqE; break; default: - error("gpio_irq only supported on port A and D\n"); + error("gpio_irq only supported on port A-E.\n"); break; } NVIC_SetVector(irq_n, vector); diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/rtc_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/rtc_api.c index 0402f585bd..f077bec565 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/rtc_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/rtc_api.c @@ -22,23 +22,17 @@ static void init(void) { // enable RTC clock SIM->SCGC6 |= SIM_SCGC6_RTC_MASK; - /* - * configure PTC1 with alternate function 1: RTC_CLKIN - * As the kl25z board does not have a 32kHz osc, - * we use an external clock generated by the - * interface chip - */ - PORTC->PCR[1] &= ~PORT_PCR_MUX_MASK; - PORTC->PCR[1] = PORT_PCR_MUX(1); - - // select RTC_CLKIN as RTC clock source + // OSC32 as source SIM->SOPT1 &= ~SIM_SOPT1_OSC32KSEL_MASK; - SIM->SOPT1 |= SIM_SOPT1_OSC32KSEL(2); + SIM->SOPT1 |= SIM_SOPT1_OSC32KSEL(0); } void rtc_init(void) { init(); + // Enable the oscillator + RTC_CR |= RTC_CR_OSCE_MASK; + //Configure the TSR. default value: 1 RTC->TSR = 1; diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/serial_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/serial_api.c index 6340f685e6..2356648b30 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/serial_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/serial_api.c @@ -24,20 +24,18 @@ #include "pinmap.h" #include "error.h" -/****************************************************************************** - * INITIALIZATION - ******************************************************************************/ static const PinMap PinMap_UART_TX[] = { - {PTB17, UART_0, 3}, + {PTB17, UART_0, 3}, {NC , NC , 0} }; static const PinMap PinMap_UART_RX[] = { - {PTB16, UART_0, 3}, + {PTB16, UART_0, 3}, {NC , NC , 0} }; #define UART_NUM 3 + static uint32_t serial_irq_ids[UART_NUM] = {0}; static uart_irq_handler irq_handler; @@ -49,9 +47,8 @@ void serial_init(serial_t *obj, PinName tx, PinName rx) { UARTName uart_tx = (UARTName)pinmap_peripheral(tx, PinMap_UART_TX); UARTName uart_rx = (UARTName)pinmap_peripheral(rx, PinMap_UART_RX); UARTName uart = (UARTName)pinmap_merge(uart_tx, uart_rx); - if ((int)uart == NC) { + if ((int)uart == NC) error("Serial pinout mapping failed"); - } obj->uart = (UART_Type *)uart; // enable clk @@ -63,7 +60,7 @@ void serial_init(serial_t *obj, PinName tx, PinName rx) { } // Disable UART before changing registers obj->uart->C2 &= ~(UART_C2_RE_MASK | UART_C2_TE_MASK); - + switch (uart) { case UART_0: obj->index = 0; break; case UART_1: obj->index = 1; break; @@ -94,27 +91,13 @@ void serial_free(serial_t *obj) { serial_irq_ids[obj->index] = 0; } -// serial_baud -// -// set the baud rate, taking in to account the current SystemFrequency -// -// The LPC2300 and LPC1700 have a divider and a fractional divider to control the -// baud rate. The formula is: -// -// Baudrate = (1 / PCLK) * 16 * DL * (1 + DivAddVal / MulVal) -// where: -// 1 < MulVal <= 15 -// 0 <= DivAddVal < 14 -// DivAddVal < MulVal -// void serial_baud(serial_t *obj, int baudrate) { - // save C2 state - uint8_t c2_state = (obj->uart->C2 & (UART_C2_RE_MASK | UART_C2_TE_MASK)); - + uint32_t c2_state = (obj->uart->C2 & (UART_C2_RE_MASK | UART_C2_TE_MASK)); + // Disable UART before changing registers obj->uart->C2 &= ~(UART_C2_RE_MASK | UART_C2_TE_MASK); - + // [TODO] not hardcode this value uint32_t PCLK = (obj->uart == UART0) ? 48000000u : 24000000u; @@ -129,27 +112,26 @@ void serial_baud(serial_t *obj, int baudrate) { // set BDH and BDL obj->uart->BDH = (obj->uart->BDH & ~(0x1f)) | ((DL >> 8) & 0x1f); obj->uart->BDL = (obj->uart->BDL & ~(0xff)) | ((DL >> 0) & 0xff); - + // restore C2 state obj->uart->C2 |= c2_state; } void serial_format(serial_t *obj, int data_bits, SerialParity parity, int stop_bits) { - // uint8_t m10 = 0; - + // save C2 state - uint8_t c2_state = (obj->uart->C2 & (UART_C2_RE_MASK | UART_C2_TE_MASK)); - + uint32_t c2_state = (obj->uart->C2 & (UART_C2_RE_MASK | UART_C2_TE_MASK)); + // Disable UART before changing registers obj->uart->C2 &= ~(UART_C2_RE_MASK | UART_C2_TE_MASK); - + // 8 data bits = 0 ... 9 data bits = 1 - if ((data_bits < 8) || (data_bits > 9)) { + if ((data_bits < 8) || (data_bits > 9)) error("Invalid number of bits (%d) in serial format, should be 8..9\r\n", data_bits); - } + data_bits -= 8; - uint8_t parity_enable, parity_select; + uint32_t parity_enable, parity_select; switch (parity) { case ParityNone: parity_enable = 0; parity_select = 0; break; case ParityOdd : parity_enable = 1; parity_select = 1; data_bits++; break; @@ -160,36 +142,36 @@ void serial_format(serial_t *obj, int data_bits, SerialParity parity, int stop_b } // 1 stop bits = 0, 2 stop bits = 1 - if ((stop_bits != 1) && (stop_bits != 2)) { + if ((stop_bits != 1) && (stop_bits != 2)) error("Invalid stop bits specified\r\n"); - } stop_bits -= 1; - + + uint32_t m10 = 0; + // 9 data bits + parity if (data_bits == 2) { // only uart0 supports 10 bit communication - if (obj->index != 0) { + if (obj->index != 0) error("Invalid number of bits (9) to be used with parity\r\n"); - } data_bits = 0; - //m10 = 1; + m10 = 1; } // data bits, parity and parity mode obj->uart->C1 = ((data_bits << 4) | (parity_enable << 1) | (parity_select << 0)); - - // enable 10bit mode if needed - // if (obj->index == 0) { - // obj->uart->C4 &= ~UARTLP_C4_M10_MASK; - // obj->uart->C4 |= (m10 << UARTLP_C4_M10_SHIFT); - // } - + + //enable 10bit mode if needed + if (obj->index == 0) { + obj->uart->C4 &= ~UART_C4_M10_MASK; + obj->uart->C4 |= (m10 << UART_C4_M10_SHIFT); + } + // stop bits obj->uart->BDH &= ~UART_BDH_SBR_MASK; obj->uart->BDH |= (stop_bits << UART_BDH_SBR_SHIFT); - + // restore C2 state obj->uart->C2 |= c2_state; } @@ -220,15 +202,28 @@ void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) { IRQn_Type irq_n = (IRQn_Type)0; uint32_t vector = 0; switch ((int)obj->uart) { - case UART_0: irq_n=UART0_RX_TX_IRQn; vector = (uint32_t)&uart0_irq; break; - case UART_1: irq_n=UART1_RX_TX_IRQn; vector = (uint32_t)&uart1_irq; break; - case UART_2: irq_n=UART2_RX_TX_IRQn; vector = (uint32_t)&uart2_irq; break; + case UART_0: + irq_n=UART0_RX_TX_IRQn; + vector = (uint32_t)&uart0_irq; + break; + case UART_1: + irq_n=UART1_RX_TX_IRQn; + vector = (uint32_t)&uart1_irq; + break; + case UART_2: + irq_n=UART2_RX_TX_IRQn; + vector = (uint32_t)&uart2_irq; + break; } if (enable) { switch (irq) { - case RxIrq: obj->uart->C2 |= (UART_C2_RIE_MASK); break; - case TxIrq: obj->uart->C2 |= (UART_C2_TIE_MASK); break; + case RxIrq: + obj->uart->C2 |= (UART_C2_RIE_MASK); + break; + case TxIrq: + obj->uart->C2 |= (UART_C2_TIE_MASK); + break; } NVIC_SetVector(irq_n, vector); NVIC_EnableIRQ(irq_n); @@ -237,21 +232,26 @@ void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) { int all_disabled = 0; SerialIrq other_irq = (irq == RxIrq) ? (TxIrq) : (RxIrq); switch (irq) { - case RxIrq: obj->uart->C2 &= ~(UART_C2_RIE_MASK); break; - case TxIrq: obj->uart->C2 &= ~(UART_C2_TIE_MASK); break; + case RxIrq: + obj->uart->C2 &= ~(UART_C2_RIE_MASK); + break; + case TxIrq: + obj->uart->C2 &= ~(UART_C2_TIE_MASK); + break; } switch (other_irq) { - case RxIrq: all_disabled = (obj->uart->C2 & (UART_C2_RIE_MASK)) == 0; break; - case TxIrq: all_disabled = (obj->uart->C2 & (UART_C2_TIE_MASK)) == 0; break; + case RxIrq: + all_disabled = (obj->uart->C2 & (UART_C2_RIE_MASK)) == 0; + break; + case TxIrq: + all_disabled = (obj->uart->C2 & (UART_C2_TIE_MASK)) == 0; + break; } if (all_disabled) NVIC_DisableIRQ(irq_n); } } -/****************************************************************************** - * READ/WRITE - ******************************************************************************/ int serial_getc(serial_t *obj) { while (!serial_readable(obj)); return obj->uart->D; @@ -263,7 +263,7 @@ void serial_putc(serial_t *obj, int c) { } int serial_readable(serial_t *obj) { - + return (obj->uart->S1 & UART_S1_RDRF_MASK); } @@ -280,7 +280,7 @@ void serial_pinout_tx(PinName tx) { } void serial_break_set(serial_t *obj) { - obj->uart->C2 |= UART_C2_SBK_MASK; + obj->uart->C2 |= UART_C2_SBK_MASK; } void serial_break_clear(serial_t *obj) { diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/spi_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/spi_api.c index 65f2630dfd..1fd563c868 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/spi_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/spi_api.c @@ -1,5 +1,5 @@ /* mbed Microcontroller Library - * Copyright (c) 2006-2013 ARM Limited + * Copyright (c) 2013 ARM Limited * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -24,25 +24,25 @@ static const PinMap PinMap_SPI_SCLK[] = { {PTC5, SPI_0, 2}, {PTD1, SPI_0, 2}, - {NC , NC , 0} + {NC , NC , 0} }; static const PinMap PinMap_SPI_MOSI[] = { {PTD2, SPI_0, 2}, {PTC6, SPI_0, 2}, - {NC , NC , 0} + {NC , NC , 0} }; static const PinMap PinMap_SPI_MISO[] = { {PTD3, SPI_0, 2}, {PTC7, SPI_0, 2}, - {NC , NC , 0} + {NC , NC , 0} }; static const PinMap PinMap_SPI_SSEL[] = { {PTD0, SPI_0, 2}, {PTC4, SPI_0, 2}, - {NC , NC , 0} + {NC , NC , 0} }; void spi_init(spi_t *obj, PinName mosi, PinName miso, PinName sclk, PinName ssel) { @@ -59,10 +59,11 @@ void spi_init(spi_t *obj, PinName mosi, PinName miso, PinName sclk, PinName ssel error("SPI pinout mapping failed"); } - // enable power and clocking - switch ((int)obj->spi) { - case SPI_0: SIM->SCGC5 |= 1 << 11; SIM->SCGC4 |= 1 << 22; break; - } + SIM->SCGC5 |= (1 << 11) | (1 << 12); // PortC & D + SIM->SCGC6 |= 1 << 12; // spi clocks + + // halted state + obj->spi->MCR = SPI_MCR_HALT_MASK; // set default format and frequency if (ssel == NC) { @@ -72,8 +73,10 @@ void spi_init(spi_t *obj, PinName mosi, PinName miso, PinName sclk, PinName ssel } spi_frequency(obj, 1000000); + // not halt in the debug mode + obj->spi->SR |= SPI_SR_EOQF_MASK; // enable SPI - obj->spi->MCR |= SPI_MCR_CONT_SCKE_MASK; + obj->spi->MCR &= (~SPI_MCR_HALT_MASK); // pin out the spi pins pinmap_pinout(mosi, PinMap_SPI_MOSI); @@ -88,37 +91,38 @@ void spi_free(spi_t *obj) { // [TODO] } void spi_format(spi_t *obj, int bits, int mode, int slave) { - if (bits != 8) { - error("Only 8bits SPI supported"); + if ((bits != 8) && (bits != 16)) { + error("Only 8/16 bits SPI supported"); } if ((mode < 0) || (mode > 3)) { error("SPI mode unsupported"); } - uint8_t polarity = (mode & 0x2) ? 1 : 0; - uint8_t phase = (mode & 0x1) ? 1 : 0; - uint8_t c1_data = ((!slave) << 4) | (polarity << 3) | (phase << 2); + uint32_t polarity = (mode & 0x2) ? 1 : 0; + uint32_t phase = (mode & 0x1) ? 1 : 0; - // clear MSTR, CPOL and CPHA bits + // set master/slave obj->spi->MCR &= ~SPI_MCR_MSTR_MASK; + obj->spi->MCR |= ((!slave) << SPI_MCR_MSTR_SHIFT); - // write new value - obj->spi->MCR |= c1_data; + // CTAR0 is used + obj->spi->CTAR[0] &= ~(SPI_CTAR_CPHA_MASK | SPI_CTAR_CPOL_MASK); + obj->spi->CTAR[0] |= (polarity << SPI_CTAR_CPOL_SHIFT) | (phase << SPI_CTAR_CPHA_SHIFT); } void spi_frequency(spi_t *obj, int hz) { uint32_t error = 0; uint32_t p_error = 0xffffffff; uint32_t ref = 0; - uint8_t spr = 0; - uint8_t ref_spr = 0; - uint8_t ref_prescaler = 0; + uint32_t spr = 0; + uint32_t ref_spr = 0; + uint32_t ref_prescaler = 0; // bus clk uint32_t PCLK = 48000000u; - uint8_t prescaler = 1; - uint8_t divisor = 2; + uint32_t prescaler = 1; + uint32_t divisor = 2; for (prescaler = 1; prescaler <= 8; prescaler++) { divisor = 2; @@ -140,32 +144,31 @@ void spi_frequency(spi_t *obj, int hz) { } static inline int spi_writeable(spi_t * obj) { - return 0;//(obj->spi->S & SPI_S_SPTEF_MASK) ? 1 : 0; + return (obj->spi->SR & SPI_SR_TCF_MASK) ? 1 : 0; } static inline int spi_readable(spi_t * obj) { - return 0;//(obj->spi->S & SPI_S_SPRF_MASK) ? 1 : 0; + return (obj->spi->SR & SPI_SR_TFFF_MASK) ? 1 : 0; } int spi_master_write(spi_t *obj, int value) { // wait tx buffer empty - // while(!spi_writeable(obj)); - // obj->spi->D = (value & 0xff); + while(!spi_writeable(obj)); + obj->spi->PUSHR = SPI_PUSHR_TXDATA(value & 0xff); - // // wait rx buffer full - // while (!spi_readable(obj)); - return 0;//obj->spi->D & 0xff; + // wait rx buffer full + while (!spi_readable(obj)); + return obj->spi->POPR; } int spi_slave_receive(spi_t *obj) { - return 0;//spi_readable(obj); + return spi_readable(obj); } int spi_slave_read(spi_t *obj) { - return 0;//obj->spi->D; + return obj->spi->POPR; } void spi_slave_write(spi_t *obj, int value) { - // while (!spi_writeable(obj)); - // obj->spi->D = value; + while (!spi_writeable(obj)); } diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/us_ticker.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/us_ticker.c index c58f9a06fc..090f910096 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/us_ticker.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/us_ticker.c @@ -23,9 +23,10 @@ static void lptmr_init(void); static int us_ticker_inited = 0; void us_ticker_init(void) { - if (us_ticker_inited) return; + if (us_ticker_inited) + return; us_ticker_inited = 1; - + pit_init(); lptmr_init(); } @@ -62,7 +63,7 @@ uint32_t us_ticker_read() { /****************************************************************************** * Timer Event - * + * * It schedules interrupts at given (32bit)us interval of time. * It is implemented used the 16bit Low Power Timer that remains powered in all * power modes. @@ -72,14 +73,14 @@ static void lptmr_isr(void); static void lptmr_init(void) { /* Clock the timer */ SIM->SCGC5 |= SIM_SCGC5_LPTIMER_MASK; - + /* Reset */ LPTMR0->CSR = 0; - + /* Set interrupt handler */ NVIC_SetVector(LPTimer_IRQn, (uint32_t)lptmr_isr); NVIC_EnableIRQ(LPTimer_IRQn); - + /* Clock at (1)MHz -> (1)tick/us */ LPTMR0->PSR = LPTMR_PSR_PCS(3); // OSCERCLK -> 8MHz LPTMR0->PSR |= LPTMR_PSR_PRESCALE(2); // divide by 8 @@ -99,13 +100,13 @@ static uint16_t us_ticker_int_remainder = 0; static void lptmr_set(unsigned short count) { /* Reset */ LPTMR0->CSR = 0; - + /* Set the compare register */ LPTMR0->CMR = count; - + /* Enable interrupt */ LPTMR0->CSR |= LPTMR_CSR_TIE_MASK; - + /* Start the timer */ LPTMR0->CSR |= LPTMR_CSR_TEN_MASK; } @@ -113,16 +114,16 @@ static void lptmr_set(unsigned short count) { static void lptmr_isr(void) { // write 1 to TCF to clear the LPT timer compare flag LPTMR0->CSR |= LPTMR_CSR_TCF_MASK; - + if (us_ticker_int_counter > 0) { lptmr_set(0xFFFF); us_ticker_int_counter--; - + } else { if (us_ticker_int_remainder > 0) { lptmr_set(us_ticker_int_remainder); us_ticker_int_remainder = 0; - + } else { // This function is going to disable the interrupts if there are // no other events in the queue @@ -138,7 +139,7 @@ void us_ticker_set_interrupt(unsigned int timestamp) { us_ticker_irq_handler(); return; } - + us_ticker_int_counter = (uint32_t)(delta >> 16); us_ticker_int_remainder = (uint16_t)(0xFFFF & delta); if (us_ticker_int_counter > 0) { From b73b57db2646ef7eb4e9099d1902da247e675e10 Mon Sep 17 00:00:00 2001 From: 0xc0170 Date: Mon, 23 Dec 2013 20:56:48 +0100 Subject: [PATCH 24/33] I2C, pullup --- .../TARGET_K20D5M/PeripheralNames.h | 5 +- .../TARGET_Freescale/TARGET_K20D5M/PinNames.h | 5 +- .../TARGET_K20D5M/PortNames.h | 1 + .../TARGET_Freescale/TARGET_K20D5M/i2c_api.c | 82 ++++++++----------- .../TARGET_Freescale/TARGET_K20D5M/pinmap.c | 3 +- .../TARGET_Freescale/TARGET_K20D5M/rtc_api.c | 2 +- 6 files changed, 43 insertions(+), 55 deletions(-) diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PeripheralNames.h b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PeripheralNames.h index d4b335b7e4..9253890e04 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PeripheralNames.h +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PeripheralNames.h @@ -45,9 +45,8 @@ typedef enum { PWM_6 = (0 << TPM_SHIFT) | (5), // FTM0 CH5 PWM_7 = (0 << TPM_SHIFT) | (6), // FTM0 CH6 PWM_8 = (0 << TPM_SHIFT) | (7), // FTM0 CH7 - - PWM_9 = (1 << TPM_SHIFT) | (0), // FTM1 CH0 - PWM_10 = (1 << TPM_SHIFT) | (1), // FTM1 CH1 + PWM_9 = (1 << TPM_SHIFT) | (0), // FTM1 CH0 + PWM_10 = (1 << TPM_SHIFT) | (1), // FTM1 CH1 } PWMName; typedef enum { diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PinNames.h b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PinNames.h index fb9b164229..00559e57a9 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PinNames.h +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PinNames.h @@ -235,10 +235,11 @@ typedef enum { NC = (int)0xFFFFFFFF } PinName; -/* PullDown not available for KL05 */ + typedef enum { PullNone = 0, - PullUp = 2, + PullDown = 2, + PullUp = 3, } PinMode; #ifdef __cplusplus diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PortNames.h b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PortNames.h index 84831863f3..476845b76d 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PortNames.h +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/PortNames.h @@ -31,4 +31,5 @@ typedef enum { #ifdef __cplusplus } #endif + #endif diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/i2c_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/i2c_api.c index 27a3b734a1..8fd1d30055 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/i2c_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/i2c_api.c @@ -20,25 +20,14 @@ #include "error.h" static const PinMap PinMap_I2C_SDA[] = { - {PTE25, I2C_0, 5}, - {PTC9, I2C_0, 2}, - {PTE0, I2C_0, 6}, {PTB1, I2C_0, 2}, {PTB3, I2C_0, 2}, - {PTC11, I2C_0, 2}, - {PTC2, I2C_0, 2}, - {PTA4, I2C_0, 2}, {NC , NC , 0} }; static const PinMap PinMap_I2C_SCL[] = { - {PTE24, I2C_0, 5}, - {PTC8, I2C_0, 2}, - {PTE1, I2C_0, 6}, {PTB0, I2C_0, 2}, {PTB2, I2C_0, 2}, - {PTC10, I2C_0, 2}, - {PTC1, I2C_0, 2}, {NC , NC, 0} }; @@ -66,15 +55,11 @@ void i2c_init(i2c_t *obj, PinName sda, PinName scl) { I2CName i2c_sda = (I2CName)pinmap_peripheral(sda, PinMap_I2C_SDA); I2CName i2c_scl = (I2CName)pinmap_peripheral(scl, PinMap_I2C_SCL); obj->i2c = (I2C_Type*)pinmap_merge(i2c_sda, i2c_scl); - if ((int)obj->i2c == NC) { + if ((int)obj->i2c == NC) error("I2C pin mapping failed"); - } - // enable power - switch ((int)obj->i2c) { - case I2C_0: SIM->SCGC5 |= 1 << 13; SIM->SCGC4 |= 1 << 6; break; - //case I2C_1: SIM->SCGC5 |= 1 << 11; SIM->SCGC4 |= 1 << 7; break; - } + SIM->SCGC4 |= SIM_SCGC4_I2C0_MASK; + SIM->SCGC5 |= SIM_SCGC5_PORTB_MASK; // set default frequency at 100k i2c_frequency(obj, 100000); @@ -84,12 +69,12 @@ void i2c_init(i2c_t *obj, PinName sda, PinName scl) { pinmap_pinout(sda, PinMap_I2C_SDA); pinmap_pinout(scl, PinMap_I2C_SCL); - + first_read = 1; } int i2c_start(i2c_t *obj) { - uint8_t temp; + uint32_t temp; volatile int i; // if we are in the middle of a transaction // activate the repeat_start flag @@ -118,19 +103,20 @@ int i2c_stop(i2c_t *obj) { // when there is no waiting time after a STOP. // This wait is also included on the samples // code provided with the freedom board - for (n = 0; n < 100; n++) __NOP(); + for (n = 0; n < 100; n++) + __NOP(); first_read = 1; return 0; } static int timeout_status_poll(i2c_t *obj, uint32_t mask) { uint32_t i, timeout = 1000; - + for (i = 0; i < timeout; i++) { if (obj->i2c->S & mask) return 0; } - + return 1; } @@ -139,14 +125,14 @@ static int timeout_status_poll(i2c_t *obj, uint32_t mask) { // 1: OK ack not received // 2: failure static int i2c_wait_end_tx_transfer(i2c_t *obj) { - + // wait for the interrupt flag if (timeout_status_poll(obj, I2C_S_IICIF_MASK)) { return 2; } - + obj->i2c->S |= I2C_S_IICIF_MASK; - + // wait transfer complete if (timeout_status_poll(obj, I2C_S_TCF_MASK)) { return 2; @@ -164,9 +150,9 @@ static int i2c_wait_end_rx_transfer(i2c_t *obj) { if (timeout_status_poll(obj, I2C_S_IICIF_MASK)) { return 1; } - + obj->i2c->S |= I2C_S_IICIF_MASK; - + return 0; } @@ -301,33 +287,33 @@ void i2c_reset(i2c_t *obj) { int i2c_byte_read(i2c_t *obj, int last) { char data; - + // set rx mode obj->i2c->C1 &= ~I2C_C1_TX_MASK; - + if(first_read) { // first dummy read i2c_do_read(obj, &data, 0); first_read = 0; } - + if (last) { // set tx mode obj->i2c->C1 |= I2C_C1_TX_MASK; return obj->i2c->D; } - + i2c_do_read(obj, &data, last); - + return data; } int i2c_byte_write(i2c_t *obj, int data) { first_read = 1; - + // set tx mode obj->i2c->C1 |= I2C_C1_TX_MASK; - + return !i2c_do_write(obj, (data & 0xFF)); } @@ -348,10 +334,10 @@ int i2c_slave_receive(i2c_t *obj) { switch(obj->i2c->S) { // read addressed case 0xE6: return 1; - + // write addressed case 0xE2: return 3; - + default: return 0; } } @@ -360,26 +346,26 @@ int i2c_slave_read(i2c_t *obj, char *data, int length) { uint8_t dummy_read; uint8_t * ptr; int count; - + // set rx mode obj->i2c->C1 &= ~I2C_C1_TX_MASK; - + // first dummy read dummy_read = obj->i2c->D; if(i2c_wait_end_rx_transfer(obj)) { return 0; } - + // read address dummy_read = obj->i2c->D; if(i2c_wait_end_rx_transfer(obj)) { return 0; } - + // read (length - 1) bytes for (count = 0; count < (length - 1); count++) { data[count] = obj->i2c->D; - if(i2c_wait_end_rx_transfer(obj)) { + if (i2c_wait_end_rx_transfer(obj)) { return count; } } @@ -387,32 +373,32 @@ int i2c_slave_read(i2c_t *obj, char *data, int length) { // read last byte ptr = (length == 0) ? &dummy_read : (uint8_t *)&data[count]; *ptr = obj->i2c->D; - + return (length) ? (count + 1) : 0; } int i2c_slave_write(i2c_t *obj, const char *data, int length) { int i, count = 0; - + // set tx mode obj->i2c->C1 |= I2C_C1_TX_MASK; - + for (i = 0; i < length; i++) { if(i2c_do_write(obj, data[count++]) == 2) { return i; } } - + // set rx mode obj->i2c->C1 &= ~I2C_C1_TX_MASK; - + // dummy rx transfer needed // otherwise the master cannot generate a stop bit obj->i2c->D; if(i2c_wait_end_rx_transfer(obj) == 2) { return count; } - + return count; } diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pinmap.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pinmap.c index 9bb5c3f220..9adef24d09 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pinmap.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/pinmap.c @@ -17,7 +17,8 @@ #include "error.h" void pin_function(PinName pin, int function) { - if (pin == (PinName)NC) return; + if (pin == (PinName)NC) + return; uint32_t port_n = (uint32_t)pin >> PORT_SHIFT; uint32_t pin_n = (uint32_t)(pin & 0x7C) >> 2; diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/rtc_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/rtc_api.c index f077bec565..a61141a129 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/rtc_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/rtc_api.c @@ -31,7 +31,7 @@ void rtc_init(void) { init(); // Enable the oscillator - RTC_CR |= RTC_CR_OSCE_MASK; + RTC->CR |= RTC_CR_OSCE_MASK; //Configure the TSR. default value: 1 RTC->TSR = 1; From 82aa7b7f2b67dfdef90373b703bb8b2f33ea4e57 Mon Sep 17 00:00:00 2001 From: Bogdan Marinescu Date: Tue, 24 Dec 2013 23:05:00 +0200 Subject: [PATCH 25/33] Enable RTOS with GCC_CR 1. Provide the required __end__ symbol 2. Call software_init_hook() if present, which in turn starts the RTOS The fix was applied for all targets with a TOOLCHAIN_GCC_CR folder, but it only works with LPC1768 and LPC4088 because of incomplete or missing support for GCC_CR and/or the RTOS for the other targets. Tested by running RTOS_1, RTOS_2 and RTOS_3 with LPC1768 and LPC4088. --- .../TOOLCHAIN_GCC_CR/LPC11U24.ld | 1 + .../TOOLCHAIN_GCC_CR/startup_LPC11xx.cpp | 16 +++++++--- .../TOOLCHAIN_GCC_CR/startup_LPC11xx.cpp | 16 +++++++--- .../TOOLCHAIN_GCC_CR/LPC1768.ld | 1 + .../TOOLCHAIN_GCC_CR/startup_LPC17xx.cpp | 16 +++++++--- .../TOOLCHAIN_GCC_CR/LPC407x_8x.ld | 1 + .../TOOLCHAIN_GCC_CR/startup_lpc407x_8x.cpp | 23 +++++++------ .../TOOLCHAIN_GCC_CR/startup_LPC43xx.cpp | 32 +++++++++++-------- 8 files changed, 69 insertions(+), 37 deletions(-) diff --git a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11UXX/TOOLCHAIN_GCC_CR/LPC11U24.ld b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11UXX/TOOLCHAIN_GCC_CR/LPC11U24.ld index b0dd012dd7..7a885a65e5 100644 --- a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11UXX/TOOLCHAIN_GCC_CR/LPC11U24.ld +++ b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11UXX/TOOLCHAIN_GCC_CR/LPC11U24.ld @@ -145,6 +145,7 @@ SECTIONS . = ALIGN(4) ; _ebss = .; PROVIDE(end = .); + __end__ = .; } > RamLoc8 PROVIDE(_pvHeapStart = .); diff --git a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11UXX/TOOLCHAIN_GCC_CR/startup_LPC11xx.cpp b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11UXX/TOOLCHAIN_GCC_CR/startup_LPC11xx.cpp index ffcb738df4..68163d3abd 100644 --- a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11UXX/TOOLCHAIN_GCC_CR/startup_LPC11xx.cpp +++ b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11UXX/TOOLCHAIN_GCC_CR/startup_LPC11xx.cpp @@ -9,7 +9,7 @@ extern "C" { void ResetISR (void); WEAK void NMI_Handler (void); WEAK void HardFault_Handler (void); -WEAK void SVCall_Handler (void); +WEAK void SVC_Handler (void); WEAK void PendSV_Handler (void); WEAK void SysTick_Handler (void); WEAK void IntDefaultHandler (void); @@ -57,7 +57,7 @@ void (* const g_pfnVectors[])(void) = { 0, 0, 0, - SVCall_Handler, + SVC_Handler, 0, 0, PendSV_Handler, @@ -113,6 +113,8 @@ extern unsigned int __data_section_table; extern unsigned int __data_section_table_end; extern unsigned int __bss_section_table_end; +extern "C" void software_init_hook(void) __attribute__((weak)); + AFTER_VECTORS void ResetISR(void) { unsigned int LoadAddr, ExeAddr, SectionLen; unsigned int *SectionTableAddr; @@ -134,14 +136,18 @@ AFTER_VECTORS void ResetISR(void) { } SystemInit(); - __libc_init_array(); - main(); + if (software_init_hook) // give control to the RTOS + software_init_hook(); // this will also call __libc_init_array + else { + __libc_init_array(); + main(); + } while (1) {;} } AFTER_VECTORS void NMI_Handler (void) {while(1){}} AFTER_VECTORS void HardFault_Handler(void) {while(1){}} -AFTER_VECTORS void SVCall_Handler (void) {while(1){}} +AFTER_VECTORS void SVC_Handler (void) {while(1){}} AFTER_VECTORS void PendSV_Handler (void) {while(1){}} AFTER_VECTORS void SysTick_Handler (void) {while(1){}} AFTER_VECTORS void IntDefaultHandler(void) {while(1){}} diff --git a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11XX_11CXX/TOOLCHAIN_GCC_CR/startup_LPC11xx.cpp b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11XX_11CXX/TOOLCHAIN_GCC_CR/startup_LPC11xx.cpp index ffcb738df4..08f1d551c9 100644 --- a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11XX_11CXX/TOOLCHAIN_GCC_CR/startup_LPC11xx.cpp +++ b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC11XX_11CXX/TOOLCHAIN_GCC_CR/startup_LPC11xx.cpp @@ -9,7 +9,7 @@ extern "C" { void ResetISR (void); WEAK void NMI_Handler (void); WEAK void HardFault_Handler (void); -WEAK void SVCall_Handler (void); +WEAK void SVC_Handler (void); WEAK void PendSV_Handler (void); WEAK void SysTick_Handler (void); WEAK void IntDefaultHandler (void); @@ -57,7 +57,7 @@ void (* const g_pfnVectors[])(void) = { 0, 0, 0, - SVCall_Handler, + SVC_Handler, 0, 0, PendSV_Handler, @@ -113,6 +113,8 @@ extern unsigned int __data_section_table; extern unsigned int __data_section_table_end; extern unsigned int __bss_section_table_end; +extern "C" void software_init_hook(void) __attribute__((weak)); + AFTER_VECTORS void ResetISR(void) { unsigned int LoadAddr, ExeAddr, SectionLen; unsigned int *SectionTableAddr; @@ -134,14 +136,18 @@ AFTER_VECTORS void ResetISR(void) { } SystemInit(); - __libc_init_array(); - main(); + if (software_init_hook) // give control to the RTOS + software_init_hook(); // this will also call __libc_init_array + else { + __libc_init_array(); + main(); + } while (1) {;} } AFTER_VECTORS void NMI_Handler (void) {while(1){}} AFTER_VECTORS void HardFault_Handler(void) {while(1){}} -AFTER_VECTORS void SVCall_Handler (void) {while(1){}} +AFTER_VECTORS void SVC_Handler (void) {while(1){}} AFTER_VECTORS void PendSV_Handler (void) {while(1){}} AFTER_VECTORS void SysTick_Handler (void) {while(1){}} AFTER_VECTORS void IntDefaultHandler(void) {while(1){}} diff --git a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC176X/TOOLCHAIN_GCC_CR/LPC1768.ld b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC176X/TOOLCHAIN_GCC_CR/LPC1768.ld index 3ac1c780f3..e67c273680 100644 --- a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC176X/TOOLCHAIN_GCC_CR/LPC1768.ld +++ b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC176X/TOOLCHAIN_GCC_CR/LPC1768.ld @@ -146,6 +146,7 @@ SECTIONS . = ALIGN(4) ; _ebss = .; PROVIDE(end = .); + __end__ = .; } > RamLoc32 PROVIDE(_pvHeapStart = .); diff --git a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC176X/TOOLCHAIN_GCC_CR/startup_LPC17xx.cpp b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC176X/TOOLCHAIN_GCC_CR/startup_LPC17xx.cpp index 5390dec3a7..4da3084c32 100644 --- a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC176X/TOOLCHAIN_GCC_CR/startup_LPC17xx.cpp +++ b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC176X/TOOLCHAIN_GCC_CR/startup_LPC17xx.cpp @@ -22,7 +22,7 @@ WEAK void HardFault_Handler (void); WEAK void MemManage_Handler (void); WEAK void BusFault_Handler (void); WEAK void UsageFault_Handler(void); -WEAK void SVCall_Handler (void); +WEAK void SVC_Handler (void); WEAK void DebugMon_Handler (void); WEAK void PendSV_Handler (void); WEAK void SysTick_Handler (void); @@ -75,7 +75,7 @@ void (* const g_pfnVectors[])(void) = { 0, 0, 0, - SVCall_Handler, + SVC_Handler, DebugMon_Handler, 0, PendSV_Handler, @@ -130,6 +130,8 @@ AFTER_VECTORS void bss_init(unsigned int start, unsigned int len) { for (loop = 0; loop < len; loop = loop + 4) *pulDest++ = 0; } +extern "C" void software_init_hook(void) __attribute__((weak)); + AFTER_VECTORS void ResetISR(void) { unsigned int LoadAddr, ExeAddr, SectionLen; unsigned int *SectionTableAddr; @@ -149,8 +151,12 @@ AFTER_VECTORS void ResetISR(void) { } SystemInit(); - __libc_init_array(); - main(); + if (software_init_hook) // give control to the RTOS + software_init_hook(); // this will also call __libc_init_array + else { + __libc_init_array(); + main(); + } while (1) {;} } @@ -159,7 +165,7 @@ AFTER_VECTORS void HardFault_Handler (void) {} AFTER_VECTORS void MemManage_Handler (void) {} AFTER_VECTORS void BusFault_Handler (void) {} AFTER_VECTORS void UsageFault_Handler(void) {} -AFTER_VECTORS void SVCall_Handler (void) {} +AFTER_VECTORS void SVC_Handler (void) {} AFTER_VECTORS void DebugMon_Handler (void) {} AFTER_VECTORS void PendSV_Handler (void) {} AFTER_VECTORS void SysTick_Handler (void) {} diff --git a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_CR/LPC407x_8x.ld b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_CR/LPC407x_8x.ld index b6b2361267..8da20f62aa 100644 --- a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_CR/LPC407x_8x.ld +++ b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_CR/LPC407x_8x.ld @@ -156,6 +156,7 @@ SECTIONS . = ALIGN(4) ; _ebss = .; PROVIDE(end = .); + __end__ = .; } > RamLoc64 /* NOINIT section for RamPeriph32 */ diff --git a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_CR/startup_lpc407x_8x.cpp b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_CR/startup_lpc407x_8x.cpp index 7e056d2d36..122f8abc80 100644 --- a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_CR/startup_lpc407x_8x.cpp +++ b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC408X/TOOLCHAIN_GCC_CR/startup_lpc407x_8x.cpp @@ -259,6 +259,9 @@ extern unsigned int __bss_section_table_end; // Sets up a simple runtime environment and initializes the C/C++ // library. //***************************************************************************** + +extern "C" void software_init_hook(void) __attribute__((weak)); + __attribute__ ((section(".after_vectors"))) void ResetISR(void) { @@ -319,21 +322,23 @@ ResetISR(void) { //#ifdef __USE_CMSIS SystemInit(); //#endif - + if (software_init_hook) // give control to the RTOS + software_init_hook(); // this will also call __libc_init_array + else { #if defined (__cplusplus) - // - // Call C++ library initialisation - // - __libc_init_array(); + // + // Call C++ library initialisation + // + __libc_init_array(); #endif #if defined (__REDLIB__) - // Call the Redlib library, which in turn calls main() - __main() ; + // Call the Redlib library, which in turn calls main() + __main() ; #else - main(); + main(); #endif - + } // // main() shouldn't return, but if it does, we'll just enter an infinite loop // diff --git a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC43XX/TOOLCHAIN_GCC_CR/startup_LPC43xx.cpp b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC43XX/TOOLCHAIN_GCC_CR/startup_LPC43xx.cpp index e27fa6fcd8..c1697d325d 100644 --- a/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC43XX/TOOLCHAIN_GCC_CR/startup_LPC43xx.cpp +++ b/libraries/mbed/targets/cmsis/TARGET_NXP/TARGET_LPC43XX/TOOLCHAIN_GCC_CR/startup_LPC43xx.cpp @@ -312,6 +312,9 @@ extern unsigned int __bss_section_table_end; // library. // // ***************************************************************************** + +extern "C" void software_init_hook(void) __attribute__((weak)); + void ResetISR(void) { @@ -342,20 +345,23 @@ ResetISR(void) { bss_init(ExeAddr, SectionLen); } - #if defined(__cplusplus) - // - // Call C++ library initialisation - // - __libc_init_array(); - #endif - - #if defined(__REDLIB__) - // Call the Redlib library, which in turn calls main() - __main(); - #else - main(); - #endif + if (software_init_hook) // give control to the RTOS + software_init_hook(); // this will also call __libc_init_array + else { + #if defined(__cplusplus) + // + // Call C++ library initialisation + // + __libc_init_array(); + #endif + #if defined(__REDLIB__) + // Call the Redlib library, which in turn calls main() + __main(); + #else + main(); + #endif + } // // main() shouldn't return, but if it does, we'll just enter an infinite loop // From 78140c4aa18c53fe07f220968315b1b815ff79a5 Mon Sep 17 00:00:00 2001 From: 0xc0170 Date: Wed, 25 Dec 2013 20:02:56 +0100 Subject: [PATCH 26/33] LPTMR timer - OSCEN set, GCC startup vectors add --- .../TOOLCHAIN_ARM_STD/MK20D5.sct | 2 +- .../TOOLCHAIN_GCC_ARM/startup_MK20D5.s | 79 +++++++++++-------- .../TARGET_K20D5M/cmsis_nvic.h | 4 +- .../TARGET_K20D5M/analogin_api.c | 4 +- .../TARGET_K20D5M/gpio_irq_api.c | 9 ++- .../TARGET_Freescale/TARGET_K20D5M/i2c_api.c | 32 ++++---- .../TARGET_K20D5M/us_ticker.c | 4 +- 7 files changed, 72 insertions(+), 62 deletions(-) diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/MK20D5.sct b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/MK20D5.sct index 96520733dc..9a661627b7 100644 --- a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/MK20D5.sct +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_ARM_STD/MK20D5.sct @@ -5,7 +5,7 @@ LR_IROM1 0x00000000 0x20000 { ; load region size_region (132k) *(InRoot$$Sections) .ANY (+RO) } - ; 8_byte_aligned(61 vect * 4 bytes) = 8_byte_aligned(0xF4) = 0xF8 + ; 8_byte_aligned(62 vect * 4 bytes) = 8_byte_aligned(0xF8) = 0xF8 ; 0x4000 - 0xF8 = 0x3F08 RW_IRAM1 0x1FFFE0F8 0x3F08 { .ANY (+RW +ZI) diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/startup_MK20D5.s b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/startup_MK20D5.s index c91491787c..e062c9270c 100644 --- a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/startup_MK20D5.s +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/startup_MK20D5.s @@ -86,39 +86,52 @@ __isr_vector: .long SysTick_Handler /* SysTick Handler */ /* External interrupts */ - .long WDT_IRQHandler /* 0: Watchdog Timer */ - .long RTC_IRQHandler /* 1: Real Time Clock */ - .long TIM0_IRQHandler /* 2: Timer0 / Timer1 */ - .long TIM2_IRQHandler /* 3: Timer2 / Timer3 */ - .long MCIA_IRQHandler /* 4: MCIa */ - .long MCIB_IRQHandler /* 5: MCIb */ - .long UART0_IRQHandler /* 6: UART0 - DUT FPGA */ - .long UART1_IRQHandler /* 7: UART1 - DUT FPGA */ - .long UART2_IRQHandler /* 8: UART2 - DUT FPGA */ - .long UART4_IRQHandler /* 9: UART4 - not connected */ - .long AACI_IRQHandler /* 10: AACI / AC97 */ - .long CLCD_IRQHandler /* 11: CLCD Combined Interrupt */ - .long ENET_IRQHandler /* 12: Ethernet */ - .long USBDC_IRQHandler /* 13: USB Device */ - .long USBHC_IRQHandler /* 14: USB Host Controller */ - .long CHLCD_IRQHandler /* 15: Character LCD */ - .long FLEXRAY_IRQHandler /* 16: Flexray */ - .long CAN_IRQHandler /* 17: CAN */ - .long LIN_IRQHandler /* 18: LIN */ - .long I2C_IRQHandler /* 19: I2C ADC/DAC */ - .long 0 /* 20: Reserved */ - .long 0 /* 21: Reserved */ - .long 0 /* 22: Reserved */ - .long 0 /* 23: Reserved */ - .long 0 /* 24: Reserved */ - .long 0 /* 25: Reserved */ - .long 0 /* 26: Reserved */ - .long 0 /* 27: Reserved */ - .long CPU_CLCD_IRQHandler /* 28: Reserved - CPU FPGA CLCD */ - .long 0 /* 29: Reserved - CPU FPGA */ - .long UART3_IRQHandler /* 30: UART3 - CPU FPGA */ - .long SPI_IRQHandler /* 31: SPI Touchscreen - CPU FPGA */ - + .long DMA0_IRQHandler /* 0: Watchdog Timer */ + .long DMA1_IRQHandler /* 1: Real Time Clock */ + .long DMA2_IRQHandler /* 2: Timer0 / Timer1 */ + .long DMA3_IRQHandler /* 3: Timer2 / Timer3 */ + .long DMA_Error_IRQHandler /* 4: MCIa */ + .long 0 /* 5: MCIb */ + .long FTFL_IRQHandler /* 6: UART0 - DUT FPGA */ + .long Read_Collision_IRQHandler /* 7: UART1 - DUT FPGA */ + .long LVD_LVW_IRQHandler /* 8: UART2 - DUT FPGA */ + .long LLW_IRQHandler /* 9: UART4 - not connected */ + .long Watchdog_IRQHandler /* 10: AACI / AC97 */ + .long I2C0_IRQHandler /* 11: CLCD Combined Interrupt */ + .long SPI0_IRQHandler /* 12: Ethernet */ + .long I2S0_Tx_IRQHandler /* 13: USB Device */ + .long I2S0_Rx_IRQHandler /* 14: USB Host Controller */ + .long UART0_LON_IRQHandler /* 15: Character LCD */ + .long UART0_RX_TX_IRQHandler /* 16: Flexray */ + .long UART0_ERR_IRQHandler /* 17: CAN */ + .long UART1_RX_TX_IRQHandler /* 18: LIN */ + .long UART1_ERR_IRQHandler /* 19: I2C ADC/DAC */ + .long UART2_RX_TX_IRQHandler /* 20: Reserved */ + .long UART2_ERR_IRQHandler /* 21: Reserved */ + .long ADC0_IRQHandler /* 22: Reserved */ + .long CMP0_IRQHandler /* 23: Reserved */ + .long CMP1_IRQHandler /* 24: Reserved */ + .long FTM0_IRQHandler /* 25: Reserved */ + .long FTM1_IRQHandler /* 26: Reserved */ + .long CMT_IRQHandler /* 27: Reserved */ + .long RTC_IRQHandler /* 28: Reserved - CPU FPGA CLCD */ + .long RTC_Seconds_IRQHandler /* 29: Reserved - CPU FPGA */ + .long PIT0_IRQHandler /* 30: UART3 - CPU FPGA */ + .long PIT1_IRQHandler /* 31: SPI Touchscreen - CPU FPGA */ + .long PIT2_IRQHandler + .long PIT3_IRQHandler + .long PDB0_IRQHandler + .long USB0_IRQHandler + .long USBDCD_IRQHandler + .long TSI0_IRQHandler + .long MCG_IRQHandler + .long LPTimer_IRQHandler + .long PORTA_IRQHandler + .long PORTB_IRQHandler + .long PORTC_IRQHandler + .long PORTD_IRQHandler + .long PORTE_IRQHandler + .long SWI_IRQHandler .size __isr_vector, . - __isr_vector .text diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis_nvic.h b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis_nvic.h index 6acdca9efd..539ff8765e 100644 --- a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis_nvic.h +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/cmsis_nvic.h @@ -2,12 +2,12 @@ * Copyright (c) 2009-2011 ARM Limited. All rights reserved. * * CMSIS-style functionality to support dynamic vectors - */ + */ #ifndef MBED_CMSIS_NVIC_H #define MBED_CMSIS_NVIC_H -#define NVIC_NUM_VECTORS (16 + 32) // CORE + MCU Peripherals +#define NVIC_NUM_VECTORS (16 + 46) // CORE + MCU Peripherals #define NVIC_USER_IRQ_OFFSET 16 #include "cmsis.h" diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/analogin_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/analogin_api.c index 354c055962..ed9380b001 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/analogin_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/analogin_api.c @@ -35,9 +35,8 @@ static const PinMap PinMap_ADC[] = { void analogin_init(analogin_t *obj, PinName pin) { obj->adc = (ADCName)pinmap_peripheral(pin, PinMap_ADC); - if (obj->adc == (ADCName)NC) { + if (obj->adc == (ADCName)NC) error("ADC pin mapping failed"); - } SIM->SCGC6 |= SIM_SCGC6_ADC0_MASK; @@ -72,7 +71,6 @@ uint16_t analogin_read_u16(analogin_t *obj) { // Wait Conversion Complete while ((ADC0->SC1[0] & ADC_SC1_COCO_MASK) != ADC_SC1_COCO_MASK); - // Return value return (uint16_t)ADC0->R[0]; } diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_irq_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_irq_api.c index e71d70c870..db4d36b758 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_irq_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/gpio_irq_api.c @@ -37,7 +37,8 @@ static void handle_interrupt_in(PORT_Type *port, int ch_base) { if (port->ISFR & pmask) { mask |= pmask; uint32_t id = channel_ids[ch_base + i]; - if (id == 0) continue; + if (id == 0) + continue; GPIO_Type *gpio = PTA; gpio_irq_event event = IRQ_NONE; @@ -70,7 +71,8 @@ void gpio_irqD(void) {handle_interrupt_in(PORTD, 96);} void gpio_irqE(void) {handle_interrupt_in(PORTE, 128);} int gpio_irq_init(gpio_irq_t *obj, PinName pin, gpio_irq_handler handler, uint32_t id) { - if (pin == NC) return -1; + if (pin == NC) + return -1; irq_handler = handler; @@ -129,9 +131,8 @@ void gpio_irq_set(gpio_irq_t *obj, gpio_irq_event event, uint32_t enable) { switch (port->PCR[obj->pin] & PORT_PCR_IRQC_MASK) { case IRQ_DISABLED: - if (enable) { + if (enable) irq_settings = (event == IRQ_RISE) ? (IRQ_RAISING_EDGE) : (IRQ_FALLING_EDGE); - } break; case IRQ_RAISING_EDGE: diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/i2c_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/i2c_api.c index 8fd1d30055..ce13b81180 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/i2c_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/i2c_api.c @@ -79,12 +79,11 @@ int i2c_start(i2c_t *obj) { // if we are in the middle of a transaction // activate the repeat_start flag if (obj->i2c->S & I2C_S_BUSY_MASK) { - // KL25Z errata sheet: repeat start cannot be generated if the - // I2Cx_F[MULT] field is set to a non-zero value temp = obj->i2c->F >> 6; obj->i2c->F &= 0x3F; obj->i2c->C1 |= 0x04; - for (i = 0; i < 100; i ++) __NOP(); + for (i = 0; i < 100; i ++) + __NOP(); obj->i2c->F |= temp << 6; } else { obj->i2c->C1 |= I2C_C1_MST_MASK; @@ -274,9 +273,8 @@ int i2c_write(i2c_t *obj, int address, const char *data, int length, int stop) { } } - if (stop) { + if (stop) i2c_stop(obj); - } return length; } @@ -333,12 +331,15 @@ void i2c_slave_mode(i2c_t *obj, int enable_slave) { int i2c_slave_receive(i2c_t *obj) { switch(obj->i2c->S) { // read addressed - case 0xE6: return 1; + case 0xE6: + return 1; // write addressed - case 0xE2: return 3; + case 0xE2: + return 3; - default: return 0; + default: + return 0; } } @@ -352,22 +353,19 @@ int i2c_slave_read(i2c_t *obj, char *data, int length) { // first dummy read dummy_read = obj->i2c->D; - if(i2c_wait_end_rx_transfer(obj)) { + if (i2c_wait_end_rx_transfer(obj)) return 0; - } // read address dummy_read = obj->i2c->D; - if(i2c_wait_end_rx_transfer(obj)) { + if (i2c_wait_end_rx_transfer(obj)) return 0; - } // read (length - 1) bytes for (count = 0; count < (length - 1); count++) { data[count] = obj->i2c->D; - if (i2c_wait_end_rx_transfer(obj)) { + if (i2c_wait_end_rx_transfer(obj)) return count; - } } // read last byte @@ -384,9 +382,8 @@ int i2c_slave_write(i2c_t *obj, const char *data, int length) { obj->i2c->C1 |= I2C_C1_TX_MASK; for (i = 0; i < length; i++) { - if(i2c_do_write(obj, data[count++]) == 2) { + if (i2c_do_write(obj, data[count++]) == 2) return i; - } } // set rx mode @@ -395,9 +392,8 @@ int i2c_slave_write(i2c_t *obj, const char *data, int length) { // dummy rx transfer needed // otherwise the master cannot generate a stop bit obj->i2c->D; - if(i2c_wait_end_rx_transfer(obj) == 2) { + if (i2c_wait_end_rx_transfer(obj) == 2) return count; - } return count; } diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/us_ticker.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/us_ticker.c index 090f910096..c0da069928 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/us_ticker.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/us_ticker.c @@ -82,7 +82,9 @@ static void lptmr_init(void) { NVIC_EnableIRQ(LPTimer_IRQn); /* Clock at (1)MHz -> (1)tick/us */ - LPTMR0->PSR = LPTMR_PSR_PCS(3); // OSCERCLK -> 8MHz + OSC0->CR |= OSC_CR_ERCLKEN_MASK; + LPTMR0->PSR = 0; + LPTMR0->PSR |= LPTMR_PSR_PCS(3); // OSCERCLK -> 8MHz LPTMR0->PSR |= LPTMR_PSR_PRESCALE(2); // divide by 8 } From 6aa237fad206a328a178922a082563fe024902b0 Mon Sep 17 00:00:00 2001 From: 0xc0170 Date: Wed, 25 Dec 2013 20:29:34 +0100 Subject: [PATCH 27/33] K20D5M exporters for uVision and ARM GCC --- workspace_tools/export/gcc_arm_k20d5m.tmpl | 46 ++ workspace_tools/export/gccarm.py | 2 +- workspace_tools/export/uvision4.py | 2 +- .../export/uvision4_k20d5m.uvopt.tmpl | 204 +++++++++ .../export/uvision4_k20d5m.uvproj.tmpl | 423 ++++++++++++++++++ 5 files changed, 675 insertions(+), 2 deletions(-) create mode 100644 workspace_tools/export/gcc_arm_k20d5m.tmpl create mode 100644 workspace_tools/export/uvision4_k20d5m.uvopt.tmpl create mode 100644 workspace_tools/export/uvision4_k20d5m.uvproj.tmpl diff --git a/workspace_tools/export/gcc_arm_k20d5m.tmpl b/workspace_tools/export/gcc_arm_k20d5m.tmpl new file mode 100644 index 0000000000..a4d9e6f67d --- /dev/null +++ b/workspace_tools/export/gcc_arm_k20d5m.tmpl @@ -0,0 +1,46 @@ +# This file was automagically generated by mbed.org. For more information, +# see http://mbed.org/handbook/Exporting-to-GCC-ARM-Embedded + +GCC_BIN = +PROJECT = {{name}} +OBJECTS = {% for f in to_be_compiled %}{{f}} {% endfor %} +SYS_OBJECTS = {% for f in object_files %}{{f}} {% endfor %} +INCLUDE_PATHS = {% for p in include_paths %}-I{{p}} {% endfor %} +LIBRARY_PATHS = {% for p in library_paths %}-L{{p}} {% endfor %} +LIBRARIES = {% for lib in libraries %}-l{{lib}} {% endfor %} +LINKER_SCRIPT = {{linker_script}} + +############################################################################### +AS = $(GCC_BIN)arm-none-eabi-as +CC = $(GCC_BIN)arm-none-eabi-gcc +CPP = $(GCC_BIN)arm-none-eabi-g++ +LD = $(GCC_BIN)arm-none-eabi-gcc +OBJCOPY = $(GCC_BIN)arm-none-eabi-objcopy + +CPU = -mcpu=cortex-m4 -mthumb +CC_FLAGS = $(CPU) -c -Os -fno-common -fmessage-length=0 -Wall -fno-exceptions -ffunction-sections -fdata-sections +CC_SYMBOLS = {% for s in symbols %}-D{{s}} {% endfor %} + +LD_FLAGS = -mcpu=cortex-m4 -mthumb -Wl,--gc-sections --specs=nano.specs -u _printf_float -u _scanf_float +LD_SYS_LIBS = -lstdc++ -lsupc++ -lm -lc -lgcc -lnosys + +all: $(PROJECT).bin + +clean: + rm -f $(PROJECT).bin $(PROJECT).elf $(OBJECTS) + +.s.o: + $(AS) $(CPU) -o $@ $< + +.c.o: + $(CC) $(CC_FLAGS) $(CC_SYMBOLS) -std=gnu99 $(INCLUDE_PATHS) -o $@ $< + +.cpp.o: + $(CPP) $(CC_FLAGS) $(CC_SYMBOLS) -std=gnu++98 $(INCLUDE_PATHS) -o $@ $< + + +$(PROJECT).elf: $(OBJECTS) $(SYS_OBJECTS) + $(LD) $(LD_FLAGS) -T$(LINKER_SCRIPT) $(LIBRARY_PATHS) -o $@ $^ $(LIBRARIES) $(LD_SYS_LIBS) $(LIBRARIES) $(LD_SYS_LIBS) + +$(PROJECT).bin: $(PROJECT).elf + $(OBJCOPY) -O binary $< $@ diff --git a/workspace_tools/export/gccarm.py b/workspace_tools/export/gccarm.py index 85f40478d7..179338a0c3 100644 --- a/workspace_tools/export/gccarm.py +++ b/workspace_tools/export/gccarm.py @@ -21,7 +21,7 @@ from os.path import splitext, basename class GccArm(Exporter): NAME = 'GccArm' TOOLCHAIN = 'GCC_ARM' - TARGETS = ['LPC1768','KL05Z','KL25Z','KL46Z','LPC4088'] + TARGETS = ['LPC1768','KL05Z','KL25Z','KL46Z','K20D5M','LPC4088'] DOT_IN_RELATIVE_PATH = True def generate(self): diff --git a/workspace_tools/export/uvision4.py b/workspace_tools/export/uvision4.py index 3ab36b0c95..7954489603 100644 --- a/workspace_tools/export/uvision4.py +++ b/workspace_tools/export/uvision4.py @@ -21,7 +21,7 @@ from os.path import basename class Uvision4(Exporter): NAME = 'uVision4' - TARGETS = ['LPC1768', 'LPC11U24', 'KL05Z', 'KL25Z', 'KL46Z', 'LPC1347', 'LPC1114', 'LPC11C24', 'LPC4088', 'LPC812', 'NUCLEO_F103RB'] + TARGETS = ['LPC1768', 'LPC11U24', 'KL05Z', 'KL25Z', 'KL46Z', 'K20D5M', 'LPC1347', 'LPC1114', 'LPC11C24', 'LPC4088', 'LPC812', 'NUCLEO_F103RB'] USING_MICROLIB = ['LPC11U24', 'LPC1114', 'LPC11C24', 'LPC812', 'NUCLEO_F103RB'] diff --git a/workspace_tools/export/uvision4_k20d5m.uvopt.tmpl b/workspace_tools/export/uvision4_k20d5m.uvopt.tmpl new file mode 100644 index 0000000000..e1091dbe31 --- /dev/null +++ b/workspace_tools/export/uvision4_k20d5m.uvopt.tmpl @@ -0,0 +1,204 @@ + + + + 1.0 + +
### uVision Project, (C) Keil Software
+ + + *.c + *.s*; *.src; *.a* + *.obj + *.lib + *.txt; *.h; *.inc + *.plm + *.cpp + + + + 0 + 0 + + + + mbed FRDM-K20D5M + 0x4 + ARM-ADS + + 12000000 + + 1 + 1 + 1 + 0 + + + 1 + 65535 + 0 + 0 + 0 + + + 79 + 66 + 8 + .\build\ + + + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 0 + 0 + 0 + 0 + + + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + + + 1 + 0 + 1 + + 14 + + + 0 + Data Sheet + DATASHTS\Freescale\K20PB.pdf + + + 1 + Technical Reference Manual + datashts\arm\cortex_m4\r0p1\DDI0439C_CORTEX_M4_R0P1_TRM.PDF + + + 2 + Generic User Guide + datashts\arm\cortex_m4\r0p1\DUI0553A_CORTEX_M4_DGUG.PDF + + + + SARMCM3.DLL + + 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 + 14 + + + + + + + + + + + BIN\CMSIS_AGDI.dll + + + + 0 + ULP2CM3 + -O2510 -S0 -C0 -FO15 -FD20000000 -FC800 -FN1 -FF0MK_P128_50MHZ -FS00 -FL020000) + + + 0 + CMSIS_AGDI + -X"MBED CMSIS-DAP" -UA000000001 -O462 -S0 -C0 -N00("ARM CoreSight SW-DP") -D00(0BC11477) -L00(0) -FO15 -FD20000000 -FC800 -FN1 -FF0MK_P128_50MHZ -FS00 -FL20000 + + + + + 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_k20d5m.uvproj.tmpl b/workspace_tools/export/uvision4_k20d5m.uvproj.tmpl new file mode 100644 index 0000000000..9b306f1526 --- /dev/null +++ b/workspace_tools/export/uvision4_k20d5m.uvproj.tmpl @@ -0,0 +1,423 @@ + + + + 1.1 + +
###This file was automagically generated by mbed.org. For more information, see http://mbed.org/handbook/Exporting-To-Uvision
+ + + + mbed FRDM-K20D5M + 0x4 + ARM-ADS + + + MK20DN128xxx5 + Freescale Semiconductor + IRAM(0x1FFFE000-0x1FFFFFFF) IRAM2(0x20000000-0x20001FFF) IROM(0x0-0x1FFFF) CLOCK(12000000) CPUTYPE("Cortex-M4") ELITTLE + + "STARTUP\Freescale\Kinetis\startup_MK20D5.s" ("Freescale MK20Xxxxxxx5 Startup Code") + ULP2CM3(-O2510 -S0 -C0 -FO15 -FD20000000 -FC800 -FN1 -FF0MK_P128_50MHZ -FS00 -FL020000) + 6212 + MK20D5.H + + + + + + + + + + SFD\Freescale\Kinetis\MK20D5.sfr + 0 + + + + Freescale\Kinetis\ + Freescale\Kinetis\ + + 0 + 0 + 0 + 0 + 1 + + .\build\ + {{name}} + 1 + 0 + 0 + 1 + 1 + .\build\ + 1 + 0 + 0 + + 0 + 0 + + + 0 + 0 + 0 + 0 + + + 0 + 0 + + + 0 + 0 + + + 1 + 0 + fromelf --bin -o build\{{name}}_K20D5M.bin build\{{name}}.axf + + 0 + 0 + + 0 + + + + 0 + 0 + 0 + 0 + 0 + 1 + 0 + 0 + 0 + 0 + 3 + + + + + SARMCM3.DLL + + 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 + 14 + + + + + + + + + + + + + + BIN\CMSIS_AGDI.dll + + + + + 1 + 0 + 0 + 1 + 1 + 4105 + + BIN\CMSIS_AGDI.dll + "" () + + + + + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 1 + 1 + 0 + 1 + 1 + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + "Cortex-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 + 0x1fffe000 + 0x2000 + + + 1 + 0x0 + 0x20000 + + + 0 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x0 + + + 1 + 0x0 + 0x20000 + + + 1 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x0 + 0x0 + + + 0 + 0x1fffe000 + 0x2000 + + + 0 + 0x0 + 0x0 + + + + + + 1 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + --gnu + {% for s in symbols %} {{s}}, {% endfor %} + + {% for path in include_paths %} {{path}}; {% endfor %} + + + + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + 0 + 1 + 0 + 0x00000000 + 0x10000000 + {{scatter_file}} + + + + {% for file in object_files %} + {{file}} + {% endfor %} + + + + + + + + {% for group,files in source_files %} + + {{group}} + + {% for file in files %} + + {{file.name}} + {{file.type}} + {{file.path}} + {%if file.type == "1" %} + + + + + --c99 + + + + + {% endif %} + + {% endfor %} + + + {% endfor %} + + + + +
From 63526032d9f1e4a646e9ba04afb043c83dab540c Mon Sep 17 00:00:00 2001 From: 0xc0170 Date: Thu, 26 Dec 2013 09:03:19 +0100 Subject: [PATCH 28/33] K20D5M flash algo for template --- .../targets/hal/TARGET_Freescale/TARGET_K20D5M/i2c_api.c | 7 ------- workspace_tools/export/uvision4_k20d5m.uvopt.tmpl | 2 +- workspace_tools/export/uvision4_k20d5m.uvproj.tmpl | 4 ++-- 3 files changed, 3 insertions(+), 10 deletions(-) diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/i2c_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/i2c_api.c index ce13b81180..5762b5d142 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/i2c_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_K20D5M/i2c_api.c @@ -74,17 +74,10 @@ void i2c_init(i2c_t *obj, PinName sda, PinName scl) { } int i2c_start(i2c_t *obj) { - uint32_t temp; - volatile int i; // if we are in the middle of a transaction // activate the repeat_start flag if (obj->i2c->S & I2C_S_BUSY_MASK) { - temp = obj->i2c->F >> 6; - obj->i2c->F &= 0x3F; obj->i2c->C1 |= 0x04; - for (i = 0; i < 100; i ++) - __NOP(); - obj->i2c->F |= temp << 6; } else { obj->i2c->C1 |= I2C_C1_MST_MASK; obj->i2c->C1 |= I2C_C1_TX_MASK; diff --git a/workspace_tools/export/uvision4_k20d5m.uvopt.tmpl b/workspace_tools/export/uvision4_k20d5m.uvopt.tmpl index e1091dbe31..674bc63d41 100644 --- a/workspace_tools/export/uvision4_k20d5m.uvopt.tmpl +++ b/workspace_tools/export/uvision4_k20d5m.uvopt.tmpl @@ -145,7 +145,7 @@ 0 CMSIS_AGDI - -X"MBED CMSIS-DAP" -UA000000001 -O462 -S0 -C0 -N00("ARM CoreSight SW-DP") -D00(0BC11477) -L00(0) -FO15 -FD20000000 -FC800 -FN1 -FF0MK_P128_50MHZ -FS00 -FL20000 + -X"MBED CMSIS-DAP" -UA000000001 -O462 -S0 -C0 -N00("ARM CoreSight SW-DP") -D00(0BC11477) -L00(0) -FO15 -FD20000000 -FC800 -FN1 -FF0MK_P128_50MHZ -FS00 -FL020000 diff --git a/workspace_tools/export/uvision4_k20d5m.uvproj.tmpl b/workspace_tools/export/uvision4_k20d5m.uvproj.tmpl index 9b306f1526..3adb8921cc 100644 --- a/workspace_tools/export/uvision4_k20d5m.uvproj.tmpl +++ b/workspace_tools/export/uvision4_k20d5m.uvproj.tmpl @@ -325,8 +325,8 @@ 0 - 0x0 - 0x0 + 0x20000000 + 0x2000 From ee7c33d055aafbdcc42f1ea1ec7cd3fd3bc49c33 Mon Sep 17 00:00:00 2001 From: 0xc0170 Date: Thu, 26 Dec 2013 12:11:32 +0100 Subject: [PATCH 29/33] K20D5M default irq handler --- .../TOOLCHAIN_GCC_ARM/startup_MK20D5.s | 115 +++++++++++------- 1 file changed, 68 insertions(+), 47 deletions(-) diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/startup_MK20D5.s b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/startup_MK20D5.s index e062c9270c..d4dc59acaa 100644 --- a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/startup_MK20D5.s +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_K20D5M/TOOLCHAIN_GCC_ARM/startup_MK20D5.s @@ -1,4 +1,4 @@ -/* File: startup_ARMCM4.S +/* File: startup_MK20D5.s * Purpose: startup file for Cortex-M4 devices. Should use with * GCC for ARM Embedded Processors * Version: V1.3 @@ -134,7 +134,7 @@ __isr_vector: .long SWI_IRQHandler .size __isr_vector, . - __isr_vector - .text + .section .text.Reset_Handler .thumb .thumb_func .align 2 @@ -152,34 +152,27 @@ Reset_Handler: ldr r2, =__data_start__ ldr r3, =__data_end__ - -/* Here are two copies of loop implemenations. First one favors code size - * and the second one favors performance. Default uses the first one. - * Change to "#if 0" to use the second one */ -.flash_to_ram_loop: +.Lflash_to_ram_loop: cmp r2, r3 ittt lt ldrlt r0, [r1], #4 strlt r0, [r2], #4 - blt .flash_to_ram_loop + blt .Lflash_to_ram_loop -.flash_to_ram_loop_end: +.Lflash_to_ram_loop_end: - -#ifndef __NO_SYSTEM_INIT ldr r0, =SystemInit blx r0 -#endif - 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_irq_handler handler_name + .macro def_default_handler handler_name .align 1 .thumb_func .weak \handler_name @@ -189,40 +182,68 @@ Reset_Handler: .size \handler_name, . - \handler_name .endm - def_irq_handler NMI_Handler - def_irq_handler HardFault_Handler - def_irq_handler MemManage_Handler - def_irq_handler BusFault_Handler - def_irq_handler UsageFault_Handler - def_irq_handler SVC_Handler - def_irq_handler DebugMon_Handler - def_irq_handler PendSV_Handler - def_irq_handler SysTick_Handler - def_irq_handler Default_Handler + 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 - def_irq_handler WDT_IRQHandler - def_irq_handler RTC_IRQHandler - def_irq_handler TIM0_IRQHandler - def_irq_handler TIM2_IRQHandler - def_irq_handler MCIA_IRQHandler - def_irq_handler MCIB_IRQHandler - def_irq_handler UART0_IRQHandler - def_irq_handler UART1_IRQHandler - def_irq_handler UART2_IRQHandler - def_irq_handler UART3_IRQHandler - def_irq_handler UART4_IRQHandler - def_irq_handler AACI_IRQHandler - def_irq_handler CLCD_IRQHandler - def_irq_handler ENET_IRQHandler - def_irq_handler USBDC_IRQHandler - def_irq_handler USBHC_IRQHandler - def_irq_handler CHLCD_IRQHandler - def_irq_handler FLEXRAY_IRQHandler - def_irq_handler CAN_IRQHandler - def_irq_handler LIN_IRQHandler - def_irq_handler I2C_IRQHandler - def_irq_handler CPU_CLCD_IRQHandler - def_irq_handler SPI_IRQHandler + .macro def_irq_default_handler handler_name + .weak \handler_name + .set \handler_name, Default_Handler + .endm + + 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 DMA_Error_IRQHandler + def_irq_default_handler FTFL_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 I2C0_IRQHandler + def_irq_default_handler SPI0_IRQHandler + def_irq_default_handler I2S0_Tx_IRQHandler + def_irq_default_handler I2S0_Rx_IRQHandler + def_irq_default_handler UART0_LON_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 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 CMT_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 USBDCD_IRQHandler + def_irq_default_handler TSI0_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 DEF_IRQHandler /* Flash protection region, placed at 0x400 */ .text From 0a11767877a83c1fd2c4da5790aa268a2b138d88 Mon Sep 17 00:00:00 2001 From: ytsuboi Date: Sun, 29 Dec 2013 19:18:50 +0900 Subject: [PATCH 30/33] [LPC812] enable SPISlave --- libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC81X/device.h | 2 +- libraries/tests/mbed/spi_slave/main.cpp | 4 ++++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC81X/device.h b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC81X/device.h index 4ec1781cea..4ee3403e37 100644 --- a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC81X/device.h +++ b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC81X/device.h @@ -32,7 +32,7 @@ #define DEVICE_I2CSLAVE 0 #define DEVICE_SPI 1 -#define DEVICE_SPISLAVE 0 +#define DEVICE_SPISLAVE 1 #define DEVICE_CAN 0 diff --git a/libraries/tests/mbed/spi_slave/main.cpp b/libraries/tests/mbed/spi_slave/main.cpp index 1815102338..445df9f5bd 100644 --- a/libraries/tests/mbed/spi_slave/main.cpp +++ b/libraries/tests/mbed/spi_slave/main.cpp @@ -2,6 +2,10 @@ #if defined(TARGET_KL25Z) SPISlave device(PTD2, PTD3, PTD1, PTD0); // mosi, miso, sclk, ssel + +#elif defined(TARGET_LPC812) +SPISlave device(P0_14, P0_15, P0_12, P0_13); // mosi, miso, sclk, ssel + #else SPISlave device(p5, p6, p7, p8); // mosi, miso, sclk, ssel #endif From dc19dcbb94d039769c0878c9e96d7a7a3cdf2615 Mon Sep 17 00:00:00 2001 From: 0xc0170 Date: Mon, 30 Dec 2013 12:19:24 +0100 Subject: [PATCH 31/33] fix - KL46Z cmsis header (v2.2), shared interrupt PORTCD - Ports C and D sharing same interrupt vectors - KL46Z CMSIS header update - InterruptIn methods irq_disable/enable comment update --- libraries/mbed/api/InterruptIn.h | 6 +- .../TARGET_Freescale/TARGET_KL46Z/MKL46Z4.h | 301 +++++++++--------- .../TARGET_KL46Z/gpio_irq_api.c | 43 ++- 3 files changed, 188 insertions(+), 162 deletions(-) diff --git a/libraries/mbed/api/InterruptIn.h b/libraries/mbed/api/InterruptIn.h index 45eb2ffc54..88bc4308e8 100644 --- a/libraries/mbed/api/InterruptIn.h +++ b/libraries/mbed/api/InterruptIn.h @@ -108,11 +108,13 @@ public: */ void mode(PinMode pull); - /** Enable IRQ + /** Enable IRQ. This method depends on hw implementation, might enable one + * port interrupts. For further information, check gpio_irq_enable(). */ void enable_irq(); - /** Disable IRQ + /** Disable IRQ. This method depends on hw implementation, might disable one + * port interrupts. For further information, check gpio_irq_disable(). */ void disable_irq(); diff --git a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_KL46Z/MKL46Z4.h b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_KL46Z/MKL46Z4.h index 60588932d3..9f975d7d0a 100644 --- a/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_KL46Z/MKL46Z4.h +++ b/libraries/mbed/targets/cmsis/TARGET_Freescale/TARGET_KL46Z/MKL46Z4.h @@ -12,13 +12,13 @@ ** GNU C Compiler ** IAR ANSI C/C++ Compiler for ARM ** -** Reference manual: KL46P121M48SF4RM, Rev.1 Draft A, Aug 2012 -** Version: rev. 2.0, 2012-12-12 +** Reference manual: KL46P121M48SF4RM, Rev.2, Dec 2012 +** Version: rev. 2.2, 2013-04-12 ** ** Abstract: ** CMSIS Peripheral Access Layer for MKL46Z4 ** -** Copyright: 1997 - 2012 Freescale, Inc. All Rights Reserved. +** Copyright: 1997 - 2013 Freescale, Inc. All Rights Reserved. ** ** http: www.freescale.com ** mail: support@freescale.com @@ -28,14 +28,19 @@ ** Initial version. ** - rev. 2.0 (2012-12-12) ** Update to reference manual rev. 1. +** - rev. 2.1 (2013-04-05) +** Changed start of doxygen comment. +** - rev. 2.2 (2013-04-12) +** SystemInit function fixed for clock configuration 1. +** Name of the interrupt num. 31 updated to reflect proper function. ** ** ################################################################### */ -/** +/*! * @file MKL46Z4.h - * @version 2.0 - * @date 2012-12-12 + * @version 2.2 + * @date 2013-04-12 * @brief CMSIS Peripheral Access Layer for MKL46Z4 * * CMSIS Peripheral Access Layer for MKL46Z4 @@ -48,14 +53,14 @@ * compatible) */ #define MCU_MEM_MAP_VERSION 0x0200u /** Memory map minor version */ -#define MCU_MEM_MAP_VERSION_MINOR 0x0000u +#define MCU_MEM_MAP_VERSION_MINOR 0x0002u /* ---------------------------------------------------------------------------- -- Interrupt vector numbers ---------------------------------------------------------------------------- */ -/** +/*! * @addtogroup Interrupt_vector_numbers Interrupt vector numbers * @{ */ @@ -101,10 +106,10 @@ typedef enum IRQn { LPTimer_IRQn = 28, /**< LPTimer interrupt */ LCD_IRQn = 29, /**< Segment LCD Interrupt */ PORTA_IRQn = 30, /**< Port A interrupt */ - PORTD_IRQn = 31 /**< Port D interrupt */ + PORTC_PORTD_IRQn = 31 /**< Port C and port D interrupt */ } IRQn_Type; -/** +/*! * @} */ /* end of group Interrupt_vector_numbers */ @@ -113,7 +118,7 @@ typedef enum IRQn { -- Cortex M0 Core Configuration ---------------------------------------------------------------------------- */ -/** +/*! * @addtogroup Cortex_Core_Configuration Cortex M0 Core Configuration * @{ */ @@ -127,7 +132,7 @@ typedef enum IRQn { #include "core_cm0plus.h" /* Core Peripheral Access Layer */ #include "system_MKL46Z4.h" /* Device specific configuration file */ -/** +/*! * @} */ /* end of group Cortex_Core_Configuration */ @@ -136,7 +141,7 @@ typedef enum IRQn { -- Device Peripheral Access Layer ---------------------------------------------------------------------------- */ -/** +/*! * @addtogroup Peripheral_access_layer Device Peripheral Access Layer * @{ */ @@ -164,7 +169,7 @@ typedef enum IRQn { -- ADC Peripheral Access Layer ---------------------------------------------------------------------------- */ -/** +/*! * @addtogroup ADC_Peripheral_Access_Layer ADC Peripheral Access Layer * @{ */ @@ -203,7 +208,7 @@ typedef struct { -- ADC Register Masks ---------------------------------------------------------------------------- */ -/** +/*! * @addtogroup ADC_Register_Masks ADC Register Masks * @{ */ @@ -351,7 +356,7 @@ typedef struct { #define ADC_CLM0_CLM0_SHIFT 0 #define ADC_CLM0_CLM0(x) (((uint32_t)(((uint32_t)(x))<ISFR & pmask) { mask |= pmask; uint32_t id = channel_ids[ch_base + i]; - if (id == 0) continue; + if (id == 0) + continue; FGPIO_Type *gpio; gpio_irq_event event = IRQ_NONE; @@ -51,7 +52,13 @@ static void handle_interrupt_in(PORT_Type *port, int ch_base) { break; case IRQ_EITHER_EDGE: - gpio = (port == PORTA) ? (FPTA) : (FPTD); + if (port == PORTA) { + gpio = FPTA; + } else if (port == PORTC) { + gpio = FPTC; + } else { + gpio = FPTD; + } event = (gpio->PDIR & pmask) ? (IRQ_RISE) : (IRQ_FALL); break; } @@ -62,11 +69,19 @@ static void handle_interrupt_in(PORT_Type *port, int ch_base) { port->ISFR = mask; } -void gpio_irqA(void) {handle_interrupt_in(PORTA, 0);} -void gpio_irqD(void) {handle_interrupt_in(PORTD, 32);} +void gpio_irqA(void) { + handle_interrupt_in(PORTA, 0); +} + +void gpio_irqCD(void) { + /* PORTC and PORTD share same vector */ + handle_interrupt_in(PORTC, 32); + handle_interrupt_in(PORTD, 64); +} int gpio_irq_init(gpio_irq_t *obj, PinName pin, gpio_irq_handler handler, uint32_t id) { - if (pin == NC) return -1; + if (pin == NC) + return -1; irq_handler = handler; @@ -80,12 +95,16 @@ int gpio_irq_init(gpio_irq_t *obj, PinName pin, gpio_irq_handler handler, uint32 ch_base = 0; irq_n = PORTA_IRQn; vector = (uint32_t)gpio_irqA; break; + case PortC: + ch_base = 32; irq_n = PORTC_PORTD_IRQn; vector = (uint32_t)gpio_irqCD; + break; + case PortD: - ch_base = 32; irq_n = PORTD_IRQn; vector = (uint32_t)gpio_irqD; + ch_base = 64; irq_n = PORTC_PORTD_IRQn; vector = (uint32_t)gpio_irqCD; break; default: - error("gpio_irq only supported on port A and D\n"); + error("gpio_irq only supported on port A,C and D\n"); break; } NVIC_SetVector(irq_n, vector); @@ -147,15 +166,15 @@ void gpio_irq_set(gpio_irq_t *obj, gpio_irq_event event, uint32_t enable) { void gpio_irq_enable(gpio_irq_t *obj) { if (obj->port == PortA) { NVIC_EnableIRQ(PORTA_IRQn); - } else if (obj->port == PortD) { - NVIC_EnableIRQ(PORTD_IRQn); + } else { + NVIC_EnableIRQ(PORTC_PORTD_IRQn); } } void gpio_irq_disable(gpio_irq_t *obj) { if (obj->port == PortA) { NVIC_DisableIRQ(PORTA_IRQn); - } else if (obj->port == PortD) { - NVIC_DisableIRQ(PORTD_IRQn); + } else { + NVIC_DisableIRQ(PORTC_PORTD_IRQn); } } From aa501c003b3f0acd668f3d1cd687154ca3248553 Mon Sep 17 00:00:00 2001 From: 0xc0170 Date: Tue, 31 Dec 2013 08:34:12 +0100 Subject: [PATCH 32/33] Shared PORT interrupt - check improved - clocks must be enabled and also interrupt detected, otherwise interrupt handler is not invoked. --- .../hal/TARGET_Freescale/TARGET_KL46Z/gpio_irq_api.c | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_KL46Z/gpio_irq_api.c b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_KL46Z/gpio_irq_api.c index a71993b7d6..005ae3a367 100644 --- a/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_KL46Z/gpio_irq_api.c +++ b/libraries/mbed/targets/hal/TARGET_Freescale/TARGET_KL46Z/gpio_irq_api.c @@ -73,10 +73,13 @@ void gpio_irqA(void) { handle_interrupt_in(PORTA, 0); } +/* PORTC and PORTD share same vector */ void gpio_irqCD(void) { - /* PORTC and PORTD share same vector */ - handle_interrupt_in(PORTC, 32); - handle_interrupt_in(PORTD, 64); + if ((SIM->SCGC5 & SIM_SCGC5_PORTC_MASK) && (PORTC->ISFR)) { + handle_interrupt_in(PORTC, 32); + } else if ((SIM->SCGC5 & SIM_SCGC5_PORTD_MASK) && (PORTD->ISFR)) { + handle_interrupt_in(PORTD, 64); + } } int gpio_irq_init(gpio_irq_t *obj, PinName pin, gpio_irq_handler handler, uint32_t id) { From 4fbf286ee3de7f5f042da2b437cb43fb413e04be Mon Sep 17 00:00:00 2001 From: ytsuboi Date: Tue, 31 Dec 2013 20:24:46 +0900 Subject: [PATCH 33/33] [LPC812] change ssp_busy() to check RXOV --- .../mbed/targets/hal/TARGET_NXP/TARGET_LPC81X/spi_api.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC81X/spi_api.c b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC81X/spi_api.c index 0a5d9797fd..e02825f13a 100644 --- a/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC81X/spi_api.c +++ b/libraries/mbed/targets/hal/TARGET_NXP/TARGET_LPC81X/spi_api.c @@ -183,9 +183,9 @@ static inline int ssp_read(spi_t *obj) { } static inline int ssp_busy(spi_t *obj) { - // TODO - return 0; -} + // checking RXOV(Receiver Overrun interrupt flag) + return obj->spi->STAT & (1 << 2); + } int spi_master_write(spi_t *obj, int value) { ssp_write(obj, value);