Added KL46Z support

pull/78/head
Michael Conners 2013-09-24 10:01:06 -04:00
parent f818f842e0
commit afcc79ad27
27 changed files with 7339 additions and 0 deletions

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,163 @@
/*
* KL25Z ARM GCC linker script file
*/
MEMORY
{
VECTORS (rx) : ORIGIN = 0x00000000, LENGTH = 0x00000400
FLASH_PROTECTION (rx) : ORIGIN = 0x00000400, LENGTH = 0x00000010
FLASH (rx) : ORIGIN = 0x00000410, LENGTH = 256K - 0x00000410
RAM (rwx) : ORIGIN = 0x1FFFE000, LENGTH = 32K
}
/* Linker script to place sections and symbol values. Should be used together
* with other linker script that defines memory regions FLASH and RAM.
* It references following symbols, which must be defined in code:
* _reset_init : Entry of reset handler
*
* It defines following symbols, which code can use without definition:
* __exidx_start
* __exidx_end
* __etext
* __data_start__
* __preinit_array_start
* __preinit_array_end
* __init_array_start
* __init_array_end
* __fini_array_start
* __fini_array_end
* __data_end__
* __bss_start__
* __bss_end__
* __end__
* end
* __HeapLimit
* __StackLimit
* __StackTop
* __stack
*/
ENTRY(Reset_Handler)
SECTIONS
{
.isr_vector :
{
__vector_table = .;
KEEP(*(.vector_table))
*(.text.Reset_Handler)
*(.text.System_Init)
. = ALIGN(4);
} > VECTORS
.flash_protect :
{
KEEP(*(.kinetis_flash_config_field))
. = ALIGN(4);
} > FLASH_PROTECTION
.text :
{
*(.text*)
KEEP(*(.init))
KEEP(*(.fini))
/* .ctors */
*crtbegin.o(.ctors)
*crtbegin?.o(.ctors)
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors)
*(SORT(.ctors.*))
*(.ctors)
/* .dtors */
*crtbegin.o(.dtors)
*crtbegin?.o(.dtors)
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors)
*(SORT(.dtors.*))
*(.dtors)
*(.rodata*)
KEEP(*(.eh_frame*))
} > FLASH
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > FLASH
__exidx_start = .;
.ARM.exidx :
{
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
} > FLASH
__exidx_end = .;
__etext = .;
.data : AT (__etext)
{
__data_start__ = .;
*(vtable)
*(.data*)
. = ALIGN(4);
/* preinit data */
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP(*(.preinit_array))
PROVIDE_HIDDEN (__preinit_array_end = .);
. = ALIGN(4);
/* init data */
PROVIDE_HIDDEN (__init_array_start = .);
KEEP(*(SORT(.init_array.*)))
KEEP(*(.init_array))
PROVIDE_HIDDEN (__init_array_end = .);
. = ALIGN(4);
/* finit data */
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP(*(SORT(.fini_array.*)))
KEEP(*(.fini_array))
PROVIDE_HIDDEN (__fini_array_end = .);
. = ALIGN(4);
/* All data end */
__data_end__ = .;
} > RAM
.bss :
{
__bss_start__ = .;
*(.bss*)
*(COMMON)
__bss_end__ = .;
} > RAM
.heap :
{
__end__ = .;
end = __end__;
*(.heap*)
__HeapLimit = .;
} > RAM
/* .stack_dummy section doesn't contains any symbols. It is only
* used for linker to calculate size of stack sections, and assign
* values to stack symbols later */
.stack_dummy :
{
*(.stack)
} > RAM
/* Set stack top to end of RAM, and stack limit move down by
* size of stack_dummy section */
__StackTop = ORIGIN(RAM) + LENGTH(RAM);
__StackLimit = __StackTop - SIZEOF(.stack_dummy);
PROVIDE(__stack = __StackTop);
/* Check if data + heap + stack exceeds RAM limit */
ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed with stack")
}

View File

@ -0,0 +1,240 @@
/* KL25Z startup ARM GCC
* Purpose: startup file for Cortex-M0 devices. Should use with
* GCC for ARM Embedded Processors
* Version: V1.2
* Date: 15 Nov 2011
*
* Copyright (c) 2011, ARM Limited
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in the
documentation and/or other materials provided with the distribution.
* Neither the name of the ARM Limited nor the
names of its contributors may be used to endorse or promote products
derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL ARM LIMITED BE LIABLE FOR ANY
* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
.syntax unified
.arch armv6-m
/* Memory Model
The HEAP starts at the end of the DATA section and grows upward.
The STACK starts at the end of the RAM and grows downward.
The HEAP and stack STACK are only checked at compile time:
(DATA_SIZE + HEAP_SIZE + STACK_SIZE) < RAM_SIZE
This is just a check for the bare minimum for the Heap+Stack area before
aborting compilation, it is not the run time limit:
Heap_Size + Stack_Size = 0x80 + 0x80 = 0x100
*/
.section .stack
.align 3
#ifdef __STACK_SIZE
.equ Stack_Size, __STACK_SIZE
#else
.equ Stack_Size, 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, 0x80
#endif
.globl __HeapBase
.globl __HeapLimit
__HeapBase:
.space Heap_Size
.size __HeapBase, . - __HeapBase
__HeapLimit:
.size __HeapLimit, . - __HeapLimit
.section .vector_table,"a",%progbits
.align 2
.globl __isr_vector
__isr_vector:
.long __StackTop /* Top of Stack */
.long Reset_Handler /* Reset Handler */
.long NMI_Handler /* NMI Handler */
.long HardFault_Handler /* Hard Fault Handler */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long SVC_Handler /* SVCall Handler */
.long 0 /* Reserved */
.long 0 /* Reserved */
.long PendSV_Handler /* PendSV Handler */
.long SysTick_Handler /* SysTick Handler */
/* External interrupts */
.long DMA0_IRQHandler /* DMA channel 0 transfer complete interrupt */
.long DMA1_IRQHandler /* DMA channel 1 transfer complete interrupt */
.long DMA2_IRQHandler /* DMA channel 2 transfer complete interrupt */
.long DMA3_IRQHandler /* DMA channel 3 transfer complete interrupt */
.long Default_Handler /* Reserved interrupt 20 */
.long FTFA_IRQHandler /* FTFA interrupt */
.long LVD_LVW_IRQHandler /* Low Voltage Detect, Low Voltage Warning */
.long LLW_IRQHandler /* Low Leakage Wakeup */
.long I2C0_IRQHandler /* I2C0 interrupt */
.long I2C1_IRQHandler /* I2C0 interrupt 25 */
.long SPI0_IRQHandler /* SPI0 interrupt */
.long SPI1_IRQHandler /* SPI1 interrupt */
.long UART0_IRQHandler /* UART0 status/error interrupt */
.long UART1_IRQHandler /* UART1 status/error interrupt */
.long UART2_IRQHandler /* UART2 status/error interrupt */
.long ADC0_IRQHandler /* ADC0 interrupt */
.long CMP0_IRQHandler /* CMP0 interrupt */
.long TPM0_IRQHandler /* TPM0 fault, overflow and channels interrupt */
.long TPM1_IRQHandler /* TPM1 fault, overflow and channels interrupt */
.long TPM2_IRQHandler /* TPM2 fault, overflow and channels interrupt */
.long RTC_IRQHandler /* RTC interrupt */
.long RTC_Seconds_IRQHandler /* RTC seconds interrupt */
.long PIT_IRQHandler /* PIT timer interrupt */
.long I2S_IRQHandler /* I2S transmit interrupt */
.long USB0_IRQHandler /* USB0 interrupt */
.long DAC0_IRQHandler /* DAC interrupt */
.long TSI0_IRQHandler /* TSI0 interrupt */
.long MCG_IRQHandler /* MCG interrupt */
.long LPTimer_IRQHandler /* LPTimer interrupt */
.long LCD_IRQHandler /* Segment LCD Interrupt*/
.long PORTA_IRQHandler /* Port A interrupt */
.long PORTD_IRQHandler /* Port D interrupt */
.size __isr_vector, . - __isr_vector
.section .text.Reset_Handler
.thumb
.thumb_func
.align 2
.globl Reset_Handler
.type Reset_Handler, %function
Reset_Handler:
/* Loop to copy data from read only memory to RAM. The ranges
* of copy from/to are specified by following symbols evaluated in
* linker script.
* __etext: End of code section, i.e., begin of data sections to copy from.
* __data_start__/__data_end__: RAM address range that data should be
* copied to. Both must be aligned to 4 bytes boundary. */
ldr r1, =__etext
ldr r2, =__data_start__
ldr r3, =__data_end__
subs r3, r2
ble .flash_to_ram_loop_end
movs r4, 0
.flash_to_ram_loop:
ldr r0, [r1,r4]
str r0, [r2,r4]
adds r4, 4
cmp r4, r3
blt .flash_to_ram_loop
.flash_to_ram_loop_end:
ldr r0, =SystemInit
blx r0
ldr r0, =_start
bx r0
.pool
.size Reset_Handler, . - Reset_Handler
.text
/* Macro to define default handlers. Default handler
* will be weak symbol and just dead loops. They can be
* overwritten by other handlers */
.macro def_default_handler handler_name
.align 1
.thumb_func
.weak \handler_name
.type \handler_name, %function
\handler_name :
b .
.size \handler_name, . - \handler_name
.endm
def_default_handler NMI_Handler
def_default_handler HardFault_Handler
def_default_handler SVC_Handler
def_default_handler PendSV_Handler
def_default_handler SysTick_Handler
def_default_handler Default_Handler
def_default_handler DMA0_IRQHandler
def_default_handler DMA1_IRQHandler
def_default_handler DMA2_IRQHandler
def_default_handler DMA3_IRQHandler
def_default_handler FTFA_IRQHandler
def_default_handler LVD_LVW_IRQHandler
def_default_handler LLW_IRQHandler
def_default_handler I2C0_IRQHandler
def_default_handler 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
.weak DEF_IRQHandler
.set DEF_IRQHandler, Default_Handler
/* Flash protection region, placed at 0x400 */
.text
.thumb
.align 2
.section .kinetis_flash_config_field,"a",%progbits
kinetis_flash_config:
.long 0xffffffff
.long 0xffffffff
.long 0xffffffff
.long 0xfffffffe
.end

View File

@ -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 "MKL46Z4.h"
#include "cmsis_nvic.h"
#endif

View File

@ -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; i<NVIC_NUM_VECTORS; i++) {
vectors[i] = old_vectors[i];
}
SCB->VTOR = (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];
}

View File

@ -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

View File

@ -0,0 +1,263 @@
/*
** ###################################################################
** Processor: MKL46Z128VLK4
** Compilers: ARM Compiler
** Freescale C/C++ for Embedded ARM
** GNU C Compiler
** IAR ANSI C/C++ Compiler for ARM
**
** Reference manual: KL25RM, Rev.1, Jun 2012
** Version: rev. 1.1, 2012-06-21
**
** 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 (2012-06-13)
** Initial version.
** - rev. 1.1 (2012-06-21)
** Update according to reference manual rev. 1.
**
** ###################################################################
*/
/**
* @file MKL46Z4
* @version 1.1
* @date 2012-06-21
* @brief Device specific configuration file for MKL46Z4 (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 <stdint.h>
#include "MKL46Z4.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 = 13.98MHz
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 = 24MHz
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_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_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_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 */
/* SIM_COPC: COPT=0,COPCLKS=0,COPW=0 */
SIM->COPC = (uint32_t)0x00u;
#endif /* (DISABLE_WDOG) */
#if (CLOCK_SETUP == 0)
/* SIM->CLKDIV1: OUTDIV1=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,OUTDIV4=2,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0 */
SIM->CLKDIV1 = (uint32_t)0x00020000UL; /* 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: LOCRE0=0,??=0,RANGE0=0,HGO0=0,EREFS0=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);
/* OSC0->CR: ERCLKEN=1,??=0,EREFSTEN=0,??=0,SC2P=0,SC4P=0,SC8P=0,SC16P=0 */
OSC0->CR = (uint8_t)0x80U;
/* MCG->C5: ??=0,PLLCLKEN0=0,PLLSTEN0=0,PRDIV0=0 */
MCG->C5 = (uint8_t)0x00U;
/* MCG->C6: LOLIE0=0,PLLS=0,CME0=0,VDIV0=0 */
MCG->C6 = (uint8_t)0x00U;
while((MCG->S & MCG_S_IREFST_MASK) == 0x00U) { /* 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->SCGC5: PORTA=1 */
SIM->SCGC5 |= (uint32_t)0x0200UL; /* Enable clock gate for ports to enable pin routing */
/* SIM->CLKDIV1: OUTDIV1=1,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,OUTDIV4=1,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0 */
SIM->CLKDIV1 = (uint32_t)0x10010000UL; /* Update system prescalers */
/* PORTA->PCR18: ISF=0,MUX=0 */
PORTA->PCR[18] &= (uint32_t)~0x01000700UL;
/* PORTA->PCR19: ISF=0,MUX=0 */
PORTA->PCR[19] &= (uint32_t)~0x01000700UL;
/* Switch to FBE Mode */
/* OSC0->CR: ERCLKEN=1,??=0,EREFSTEN=0,??=0,SC2P=1,SC4P=0,SC8P=0,SC16P=1 */
OSC0->CR = (uint8_t)0x89U;
/* MCG->C2: LOCRE0=0,??=0,RANGE0=2,HGO0=0,EREFS0=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,PLLCLKEN0=0,PLLSTEN0=0,PRDIV0=1 */
MCG->C5 = (uint8_t)0x01U;
/* MCG->C6: LOLIE0=0,PLLS=0,CME0=0,VDIV0=0 */
MCG->C6 = (uint8_t)0x00U;
while((MCG->S & MCG_S_IREFST_MASK) != 0x00U) { /* Check that the source of the FLL reference clock is the external reference clock. */
}
while((MCG->S & 0x0CU) != 0x08U) { /* Wait until external reference clock is selected as MCG output */
}
/* Switch to PBE Mode */
/* MCG->C6: LOLIE0=0,PLLS=1,CME0=0,VDIV0=0 */
MCG->C6 = (uint8_t)0x40U;
while((MCG->S & 0x0CU) != 0x08U) { /* Wait until external reference clock is selected as MCG output */
}
while((MCG->S & MCG_S_LOCK0_MASK) == 0x00U) { /* 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 */
}
#elif (CLOCK_SETUP == 2)
/* SIM->SCGC5: PORTA=1 */
SIM->SCGC5 |= (uint32_t)0x0200UL; /* Enable clock gate for ports to enable pin routing */
/* SIM->CLKDIV1: OUTDIV1=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,OUTDIV4=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0,??=0 */
SIM->CLKDIV1 = (uint32_t)0x00000000UL; /* Update system prescalers */
/* PORTA->PCR18: ISF=0,MUX=0 */
PORTA->PCR[18] &= (uint32_t)~0x01000700UL;
/* PORTA->PCR19: ISF=0,MUX=0 */
PORTA->PCR[19] &= (uint32_t)~0x01000700UL;
/* Switch to FBE Mode */
/* OSC0->CR: ERCLKEN=1,??=0,EREFSTEN=0,??=0,SC2P=1,SC4P=0,SC8P=0,SC16P=1 */
OSC0->CR = (uint8_t)0x89U;
/* MCG->C2: LOCRE0=0,??=0,RANGE0=2,HGO0=0,EREFS0=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,PLLCLKEN0=0,PLLSTEN0=0,PRDIV0=0 */
MCG->C5 = (uint8_t)0x00U;
/* MCG->C6: LOLIE0=0,PLLS=0,CME0=0,VDIV0=0 */
MCG->C6 = (uint8_t)0x00U;
while((MCG->S & MCG_S_IREFST_MASK) != 0x00U) { /* Check that the source of the FLL reference clock is the external reference clock. */
}
while((MCG->S & 0x0CU) != 0x08U) { /* Wait until external reference clock is selected as MCG output */
}
/* Switch to BLPE Mode */
/* MCG->C2: LOCRE0=0,??=0,RANGE0=2,HGO0=0,EREFS0=1,LP=1,IRCS=0 */
MCG->C2 = (uint8_t)0x26U;
while((MCG->S & 0x0CU) != 0x08U) { /* Wait until external reference clock is selected as MCG output */
}
#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 */
MCGOUTClock = CPU_XTAL_CLK_HZ; /* System oscillator drives MCG clock */
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 */
MCGOUTClock = CPU_XTAL_CLK_HZ; /* System oscillator drives MCG clock */
} 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)));
}

View File

@ -0,0 +1,84 @@
/*
** ###################################################################
** Processor: MKL46Z128VLK4
** Compilers: ARM Compiler
** Freescale C/C++ for Embedded ARM
** GNU C Compiler
** IAR ANSI C/C++ Compiler for ARM
**
** Reference manual: KL25RM, Rev.1, Jun 2012
** Version: rev. 1.1, 2012-06-21
**
** 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 (2012-06-13)
** Initial version.
** - rev. 1.1 (2012-06-21)
** Update according to reference manual rev. 1.
**
** ###################################################################
*/
/**
* @file MKL46Z4
* @version 1.1
* @date 2012-06-21
* @brief Device specific configuration file for MKL46Z4 (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_MKL46Z4_H_
#define SYSTEM_MKL46Z4_H_ /**< Symbol preventing repeated inclusion */
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
/**
* @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_MKL46Z4_H_) */

View File

@ -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

View File

@ -0,0 +1,247 @@
/* 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;
#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 = PTE29,
LED_GREEN = PTD5,
LED_BLUE = PTD5,
// mbed original LED naming
LED1 = LED_GREEN,
LED2 = LED_RED,
LED3 = LED_GREEN,
LED4 = LED_RED,
// USB Pins
USBTX = PTA2,
USBRX = PTA1,
// Arduino Headers
D0 = PTA1,
D1 = PTA2,
D2 = PTD3,
D3 = PTA12,
D4 = PTA4,
D5 = PTA5,
D6 = PTC8,
D7 = PTC9,
D8 = PTA13,
D9 = PTD2,
D10 = PTD4,
D11 = PTD6,
D12 = PTD7,
D13 = PTD5,
D14 = PTE0,
D15 = PTE1,
A0 = PTC1,
A1 = PTC2,
A2 = PTB3,
A3 = PTB2,
A4 = PTB1,
A5 = PTB0,
// Not connected
NC = (int)0xFFFFFFFF
} PinName;
/* PullDown not available for KL25 */
typedef enum {
PullNone = 0,
PullUp = 2,
} PinMode;
#ifdef __cplusplus
}
#endif
#endif

View File

@ -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

View File

@ -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);
}

View File

@ -0,0 +1,86 @@
/* 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 "analogout_api.h"
#include "cmsis.h"
#include "pinmap.h"
#include "error.h"
#define RANGE_12BIT 0xFFF
static const PinMap PinMap_DAC[] = {
{PTE30, DAC_0, 0},
{NC , NC , 0}
};
void analogout_init(dac_t *obj, PinName pin) {
obj->dac = (DACName)pinmap_peripheral(pin, PinMap_DAC);
if (obj->dac == (DACName)NC) {
error("DAC pin mapping failed");
}
SIM->SCGC6 |= SIM_SCGC6_DAC0_MASK;
uint32_t port = (uint32_t)pin >> PORT_SHIFT;
SIM->SCGC5 |= 1 << (SIM_SCGC5_PORTA_SHIFT + port);
DAC0->DAT[obj->dac].DATH = 0;
DAC0->DAT[obj->dac].DATL = 0;
DAC0->C1 = DAC_C1_DACBFMD_MASK; // One-Time Scan Mode
DAC0->C0 = DAC_C0_DACEN_MASK // Enable
| DAC_C0_DACSWTRG_MASK; // Software Trigger
pinmap_pinout(pin, PinMap_DAC);
analogout_write_u16(obj, 0);
}
void analogout_free(dac_t *obj) {}
static inline void dac_write(dac_t *obj, int value) {
DAC0->DAT[obj->dac].DATL = (uint8_t)( value & 0xFF);
DAC0->DAT[obj->dac].DATH = (uint8_t)((value >> 8) & 0xFF);
}
static inline int dac_read(dac_t *obj) {
return ((DAC0->DAT[obj->dac].DATH << 8) | DAC0->DAT[obj->dac].DATL);
}
void analogout_write(dac_t *obj, float value) {
if (value < 0.0) {
dac_write(obj, 0);
} else if (value > 1.0) {
dac_write(obj, RANGE_12BIT);
} else {
dac_write(obj, value * (float)RANGE_12BIT);
}
}
void analogout_write_u16(dac_t *obj, uint16_t value) {
dac_write(obj, value >> 4); // 12-bit
}
float analogout_read(dac_t *obj) {
uint32_t value = dac_read(obj);
return (float)value * (1.0f / (float)RANGE_12BIT);
}
uint16_t analogout_read_u16(dac_t *obj) {
uint32_t value = dac_read(obj); // 12-bit
return (value << 4) | ((value >> 8) & 0x003F);
}

View File

@ -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

View File

@ -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;
FGPIO_Type *reg = (FGPIO_Type *)(FPTA_BASE + port * 0x40);
obj->reg_set = &reg->PSOR;
obj->reg_clr = &reg->PCOR;
obj->reg_in = &reg->PDIR;
obj->reg_dir = &reg->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;
}
}

View File

@ -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 <stddef.h>
#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;
FGPIO_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) ? (FPTA) : (FPTD);
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;
}

View File

@ -0,0 +1,48 @@
/* 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

View File

@ -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_1, 6},
{PTB1, I2C_0, 2},
{PTB3, I2C_0, 2},
{PTC11, I2C_1, 2},
{PTC2, I2C_1, 2},
{PTA4, I2C_1, 2},
{NC , NC , 0}
};
static const PinMap PinMap_I2C_SCL[] = {
{PTE24, I2C_0, 5},
{PTC8, I2C_0, 2},
{PTE1, I2C_1, 6},
{PTB0, I2C_0, 2},
{PTB2, I2C_0, 2},
{PTC10, I2C_1, 2},
{PTC1, I2C_1, 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

View File

@ -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 {
UARTLP_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

View File

@ -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;
}

View File

@ -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;
FGPIO_Type *reg = (FGPIO_Type *)(FPTA_BASE + port * 0x40);
obj->reg_out = &reg->PDOR;
obj->reg_in = &reg->PDIR;
obj->reg_dir = &reg->PDDR;
uint32_t i;
// The function is set per pin: reuse gpio logic
for (i=0; i<32; i++) {
if (obj->mask & (1<<i)) {
gpio_set(port_pin(obj->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<<i)) {
pin_mode(port_pin(obj->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);
}

View File

@ -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, TPM2 CH0
{LED_GREEN, PWM_10, 3}, // PTB19, TPM2 CH1
{LED_BLUE , PWM_2 , 4}, // PTD1 , TPM0 CH1
// Arduino digital pinout
{D0, PWM_9 , 3}, // PTA1 , TPM2 CH0
{D1, PWM_10, 3}, // PTA2 , TPM2 CH1
{D2, PWM_5 , 4}, // PTD4 , TPM0 CH4
{D3, PWM_7 , 3}, // PTA12, TPM1 CH0
{D4, PWM_2 , 3}, // PTA4 , TPM0 CH1
{D5, PWM_3 , 3}, // PTA5 , TPM0 CH2
{D6, PWM_5 , 3}, // PTC8 , TPM0 CH4
{D7, PWM_6 , 3}, // PTC9 , TPM0 CH5
{D8, PWM_8 , 3}, // PTA13, TPM1 CH1
{D9, PWM_6 , 4}, // PTD5 , TPM0 CH5
{D10, PWM_1 , 4}, // PTD0 , TPM0 CH0
{D11, PWM_3 , 4}, // PTD2 , TPM0 CH2
{D12, PWM_4 , 4}, // PTD3 , TPM0 CH3
{D13, PWM_2 , 4}, // PTD1 , TPM0 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 tpm_n = (pwm >> TPM_SHIFT);
unsigned int ch_n = (pwm & 0xFF);
SIM->SCGC5 |= 1 << (SIM_SCGC5_PORTA_SHIFT + port);
SIM->SCGC6 |= 1 << (SIM_SCGC6_TPM0_SHIFT + tpm_n);
SIM->SOPT2 |= SIM_SOPT2_TPMSRC(1); // Clock source: MCGFLLCLK or MCGPLLCLK
TPM_Type *tpm = (TPM_Type *)(TPM0_BASE + 0x1000 * tpm_n);
tpm->SC = TPM_SC_CMOD(1) | TPM_SC_PS(6); // (48)MHz / 64 = (0.75)MHz
tpm->CONTROLS[ch_n].CnSC = (TPM_CnSC_MSB_MASK | TPM_CnSC_ELSB_MASK); /* No Interrupts; High True pulses on Edge Aligned PWM */
obj->CnV = &tpm->CONTROLS[ch_n].CnV;
obj->MOD = &tpm->MOD;
obj->CNT = &tpm->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;
}

View File

@ -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;
}

View File

@ -0,0 +1,313 @@
/* 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 <math.h>
#include <string.h>
#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 = (UARTLP_Type *)uart;
// enable clk
switch (uart) {
case UART_0: SIM->SOPT2 |= SIM_SOPT2_PLLFLLSEL_MASK | (1<<SIM_SOPT2_UART0SRC_SHIFT);
SIM->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_SBNS_MASK;
obj->uart->BDH |= (stop_bits << UART_BDH_SBNS_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);
if (UART0->S1 & UART_S1_OR_MASK)
UART0->S1 |= UART_S1_OR_MASK;
}
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_IRQn; vector = (uint32_t)&uart0_irq; break;
case UART_1: irq_n=UART1_IRQn; vector = (uint32_t)&uart1_irq; break;
case UART_2: irq_n=UART2_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) {
// check overrun
if (obj->uart->S1 & UART_S1_OR_MASK) {
obj->uart->S1 |= UART_S1_OR_MASK;
}
return (obj->uart->S1 & UART_S1_RDRF_MASK);
}
int serial_writable(serial_t *obj) {
// check overrun
if (obj->uart->S1 & UART_S1_OR_MASK) {
obj->uart->S1 |= UART_S1_OR_MASK;
}
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;
}

View File

@ -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 <math.h>
#include "cmsis.h"
#include "pinmap.h"
#include "error.h"
static const PinMap PinMap_SPI_SCLK[] = {
{PTA15, SPI_0, 2},
{PTB11, SPI_1, 2},
{PTC5, SPI_0, 2},
{PTD1, SPI_0, 2},
{PTD5, SPI_1, 2},
{PTE2, SPI_1, 2},
{NC , NC , 0}
};
static const PinMap PinMap_SPI_MOSI[] = {
{PTA16, SPI_0, 2},
{PTA17, SPI_0, 5},
{PTB16, SPI_1, 2},
{PTB17, SPI_1, 5},
{PTC6, SPI_0, 2},
{PTC7, SPI_0, 5},
{PTD2, SPI_0, 2},
{PTD3, SPI_0, 5},
{PTD6, SPI_1, 2},
{PTD7, SPI_1, 5},
{PTE1, SPI_1, 2},
{PTE3, SPI_1, 5},
{NC , NC , 0}
};
static const PinMap PinMap_SPI_MISO[] = {
{PTA16, SPI_0, 5},
{PTA17, SPI_0, 2},
{PTB16, SPI_1, 5},
{PTB17, SPI_1, 2},
{PTC6, SPI_0, 5},
{PTC7, SPI_0, 2},
{PTD2, SPI_0, 5},
{PTD3, SPI_0, 2},
{PTD6, SPI_1, 5},
{PTD7, SPI_1, 2},
{PTE1, SPI_1, 5},
{PTE3, SPI_1, 2},
{NC , NC , 0}
};
static const PinMap PinMap_SPI_SSEL[] = {
{PTA14, SPI_0, 2},
{PTB10, SPI_1, 2},
{PTC4, SPI_0, 2},
{PTD0, SPI_0, 2},
{PTD4, SPI_1, 2},
{PTE4, SPI_1, 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->C1 |= SPI_C1_SPE_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->C1 &= ~(0x7 << 2);
// write new value
obj->spi->C1 |= 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->BR = ((ref_prescaler & 0x7) << 4) | (ref_spr & 0xf);
}
static inline int spi_writeable(spi_t * obj) {
return (obj->spi->S & SPI_S_SPTEF_MASK) ? 1 : 0;
}
static inline int spi_readable(spi_t * obj) {
return (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 obj->spi->D & 0xff;
}
int spi_slave_receive(spi_t *obj) {
return spi_readable(obj);
}
int spi_slave_read(spi_t *obj) {
return obj->spi->D;
}
void spi_slave_write(spi_t *obj, int value) {
while (!spi_writeable(obj));
obj->spi->D = value;
}

View File

@ -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 <stddef.h>
#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_CHN_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_LPTMR_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;
}
}

View File

@ -120,6 +120,18 @@ class KL25Z(Target):
self.is_disk_virtual = True
class KL46Z(Target):
def __init__(self):
Target.__init__(self)
self.core = "Cortex-M0+"
self.extra_labels = ['Freescale']
self.supported_toolchains = ["GCC_ARM"]
self.is_disk_virtual = True
class LPC812(Target):
def __init__(self):
@ -299,6 +311,7 @@ TARGETS = [
LPC11U24_301(),
KL05Z(),
KL25Z(),
KL46Z(),
LPC812(),
LPC810(),
LPC4088(),