提交 8f7ec645 编写于 作者: G geniusgogo

add Freescale k64F bsp. FRDM-K64 based

上级 b0c94dc4
/*
* K64F ARM GCC linker script file
*/
MEMORY
{
VECTORS (rx) : ORIGIN = 0x00000000, LENGTH = 0x00000400
FLASH_PROTECTION (rx) : ORIGIN = 0x00000400, LENGTH = 0x00000010
FLASH (rx) : ORIGIN = 0x00000410, LENGTH = 0x00100000 - 0x00000410
RAM (rwx) : ORIGIN = 0x1FFF0198, LENGTH = 0x00040000 - 0x00000198
}
/* 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")
}
LR_IROM1 0x00000000 0x100000 { ; load region size_region (1000k)
ER_IROM1 0x00000000 0x100000 { ; load address = execution address
*.o (RESET, +First)
*(InRoot$$Sections)
.ANY (+RO)
}
; 8_byte_aligned(62 vect * 4 bytes) = 8_byte_aligned(0x194) = 0x198
; 0x40000 - 0x198 = 0x3FE68
RW_IRAM1 0x1FFF0198 0x3FE68 {
.ANY (+RW +ZI)
}
}
# for module compiling
import os
Import('RTT_ROOT')
cwd = str(Dir('#'))
objs = []
list = os.listdir(cwd)
for d in list:
path = os.path.join(cwd, d)
if os.path.isfile(os.path.join(path, 'SConscript')):
objs = objs + SConscript(os.path.join(d, 'SConscript'))
Return('objs')
import os
import sys
import rtconfig
if os.getenv('RTT_ROOT'):
RTT_ROOT = os.getenv('RTT_ROOT')
else:
RTT_ROOT = os.path.normpath(os.getcwd() + '/../..')
sys.path = sys.path + [os.path.join(RTT_ROOT, 'tools')]
from building import *
TARGET = 'rtthread-k64f.' + rtconfig.TARGET_EXT
env = Environment(tools = ['mingw'],
AS = rtconfig.AS, ASFLAGS = rtconfig.AFLAGS,
CC = rtconfig.CC, CCFLAGS = rtconfig.CFLAGS,
AR = rtconfig.AR, ARFLAGS = '-rc',
LINK = rtconfig.LINK, LINKFLAGS = rtconfig.LFLAGS)
env.PrependENVPath('PATH', rtconfig.EXEC_PATH)
if rtconfig.PLATFORM == 'iar':
env.Replace(CCCOM = ['$CC $CCFLAGS $CPPFLAGS $_CPPDEFFLAGS $_CPPINCFLAGS -o $TARGET $SOURCES'])
env.Replace(ARFLAGS = [''])
env.Replace(LINKCOM = ['$LINK $SOURCES $LINKFLAGS -o $TARGET --map project.map'])
Export('RTT_ROOT')
Export('rtconfig')
# prepare building environment
objs = PrepareBuilding(env, RTT_ROOT, has_libcpu=False)
# build program
env.Program(TARGET, objs)
# end building
EndBuilding(TARGET)
Import('RTT_ROOT')
Import('rtconfig')
from building import *
cwd = os.path.join(str(Dir('#')), 'applications')
src = Glob('*.c')
CPPPATH = [cwd, str(Dir('#'))]
group = DefineGroup('Applications', src, depend = [''], CPPPATH = CPPPATH)
Return('group')
/*
* File : application.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
*
* Change Logs:
* Date Author Notes
*
*/
/**
* @addtogroup k64
*/
/*@{*/
#include <stdio.h>
#include "MK64F12.h"
#include <board.h>
#include <rtthread.h>
#include "led.h"
#ifdef RT_USING_LWIP
#include <lwip/sys.h>
#include <lwip/api.h>
#include <netif/ethernetif.h>
#include "stm32_eth.h"
#endif
void rt_init_thread_entry(void* parameter)
{
/* LwIP Initialization */
#ifdef RT_USING_LWIP
{
extern void lwip_sys_init(void);
/* register ethernetif device */
eth_system_device_init();
rt_hw_stm32_eth_init();
/* re-init device driver */
rt_device_init_all();
/* init lwip system */
lwip_sys_init();
rt_kprintf("TCP/IP initialized!\n");
}
#endif
//FS
//GUI
}
float f_var1;
float f_var2;
float f_var3;
float f_var4;
ALIGN(RT_ALIGN_SIZE)
static char thread_led1_stack[1024];
struct rt_thread thread_led1;
static void rt_thread_entry_led1(void* parameter)
{
int n = 0;
rt_hw_led_init();
while (1)
{
//rt_kprintf("LED\t%d\tis shining\r\n",n);
rt_hw_led_on(n);
rt_thread_delay(RT_TICK_PER_SECOND/2);
rt_hw_led_off(n);
rt_thread_delay(RT_TICK_PER_SECOND/2);
n++;
if (n == LED_MAX)
n = 0;
}
}
int rt_application_init()
{
rt_thread_t init_thread;
#if (RT_THREAD_PRIORITY_MAX == 32)
init_thread = rt_thread_create("init",
rt_init_thread_entry, RT_NULL,
2048, 8, 20);
#else
init_thread = rt_thread_create("init",
rt_init_thread_entry, RT_NULL,
2048, 80, 20);
#endif
if (init_thread != RT_NULL)
rt_thread_startup(init_thread);
//------- init led1 thread
rt_thread_init(&thread_led1,
"led_demo",
rt_thread_entry_led1,
RT_NULL,
&thread_led1_stack[0],
sizeof(thread_led1_stack),11,5);
rt_thread_startup(&thread_led1);
return 0;
}
/*@}*/
/*
* File : startup.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006, RT-Thread Develop Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://openlab.rt-thread.com/license/LICENSE
*
* Change Logs:
* Date Author Notes
*
*/
#include <rthw.h>
#include <rtthread.h>
#include <MK64F12.H>
#include <board.h>
/**
* @addtogroup k64
*/
/*@{*/
extern int rt_application_init(void);
#ifdef RT_USING_FINSH
extern void finsh_system_init(void);
extern void finsh_set_device(const char* device);
#endif
#ifdef __CC_ARM
extern int Image$$RW_IRAM1$$ZI$$Limit;
#define K64_SRAM_BEGIN (&Image$$RW_IRAM1$$ZI$$Limit)
#elif __ICCARM__
#pragma section="HEAP"
#define K64_SRAM_BEGIN (__segment_end("HEAP"))
#else
extern int __bss_end;
#define K64_SRAM_BEGIN (&__bss_end)
#endif
/*******************************************************************************
* Function Name : assert_failed
* Description : Reports the name of the source file and the source line number
* where the assert error has occurred.
* Input : - file: pointer to the source file name
* - line: assert error line source number
* Output : None
* Return : None
*******************************************************************************/
void assert_failed(rt_uint8_t* file, rt_uint32_t line)
{
rt_kprintf("\n\r Wrong parameter value detected on\r\n");
rt_kprintf(" file %s\r\n", file);
rt_kprintf(" line %d\r\n", line);
while (1) ;
}
/**
* This function will startup RT-Thread RTOS.
*/
void rtthread_startup(void)
{
/* init board */
rt_hw_board_init();
/* show version */
rt_show_version();
/* init tick */
rt_system_tick_init();
/* init kernel object */
rt_system_object_init();
/* init timer system */
rt_system_timer_init();
rt_system_heap_init((void*)K64_SRAM_BEGIN, (void*)K64_SRAM_END);
/* init scheduler system */
rt_system_scheduler_init();
/* init all device */
rt_device_init_all();
/* init application */
rt_application_init();
#ifdef RT_USING_FINSH
/* init finsh */
finsh_system_init();
finsh_set_device( FINSH_DEVICE_NAME );
#endif
/* init timer thread */
rt_system_timer_thread_init();
/* init idle thread */
rt_thread_idle_init();
/* start scheduler */
rt_system_scheduler_start();
/* never reach here */
return ;
}
int main(void)
{
/* disable interrupt first */
rt_hw_interrupt_disable();
/* startup RT-Thread RTOS */
rtthread_startup();
return 0;
}
/*@}*/
Import('RTT_ROOT')
Import('rtconfig')
from building import *
cwd = os.path.join(str(Dir('#')), 'board')
src = Glob('*.c')
src += Glob('*.s')
CPPPATH = [cwd]
group = DefineGroup('Board', src, depend = [''], CPPPATH = CPPPATH)
Return('group')
/*
* File : board.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2009 RT-Thread Develop Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
*
* Change Logs:
* Date Author Notes
*
*/
#include <rthw.h>
#include <rtthread.h>
#include <MK64F12.H>
#include "board.h"
#include "drv_uart.h"
/**
* @addtogroup K60
*/
/*@{*/
/*******************************************************************************
* Function Name : NVIC_Configuration
* Description : Configures Vector Table base location.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void NVIC_Configuration(void)
{
}
/*******************************************************************************
* Function Name : SysTick_Configuration
* Description : Configures the SysTick for OS tick.
* Input : None
* Output : None
* Return : None
*******************************************************************************/
void SysTick_Configuration(void)
{
SystemCoreClockUpdate(); /* Update Core Clock Frequency */
SysTick_Config(SystemCoreClock/RT_TICK_PER_SECOND); /* Generate interrupt each 1 ms */
}
/**
* This is the timer interrupt service routine.
*
*/
void SysTick_Handler(void)
{
/* enter interrupt */
rt_interrupt_enter();
rt_tick_increase();
/* leave interrupt */
rt_interrupt_leave();
}
/**
* This function will initial Tower board.
*/
void rt_hw_board_init()
{
/* NVIC Configuration */
NVIC_Configuration();
/* Configure the SysTick */
SysTick_Configuration();
rt_hw_uart_init();
#ifdef RT_USING_CONSOLE
rt_console_set_device(CONSOLE_DEVICE);
#endif
}
/*@}*/
/*
* File : board.h
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2009, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
*
* Change Logs:
* Date Author Notes
*
*/
// <<< Use Configuration Wizard in Context Menu >>>
#ifndef __BOARD_H__
#define __BOARD_H__
#include <MK64F12.H>
/* board configuration */
// <o> Internal SRAM memory size[Kbytes] <8-64>
// <i>Default: 64
#define K64_SRAM_SIZE 256
#define K64_SRAM_END (0x1FFF0000 + (K64_SRAM_SIZE * 1024))
//#define RT_USING_UART1
#define RT_USING_UART5
//#define RT_USING_UART3
// <o> Console on USART: <0=> no console <1=>USART 1 <2=>USART 2 <3=> USART 3
// <i>Default: 1
#define K64_CONSOLE_USART 0
void rt_hw_board_init(void);
#if K64_CONSOLE_USART == 0
#define CONSOLE_DEVICE "uart0"
#elif K64_CONSOLE_USART == 1
#define CONSOLE_DEVICE "uart1"
#elif K64_CONSOLE_USART == 2
#define CONSOLE_DEVICE "uart2"
#elif K64_CONSOLE_USART == 3
#define CONSOLE_DEVICE "uart3"
#elif K64_CONSOLE_USART == 4
#define CONSOLE_DEVICE "uart4"
#elif K64_CONSOLE_USART == 5
#define CONSOLE_DEVICE "uart5"
#endif
#define FINSH_DEVICE_NAME CONSOLE_DEVICE
#endif
// <<< Use Configuration Wizard in Context Menu >>>
/*
* File : drv_uart.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2013, RT-Thread Develop Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://openlab.rt-thread.com/license/LICENSE
*
* Change Logs:
* Date Author Notes
*
*/
#include "drv_uart.h"
static struct rt_serial_device _k64_serial; //abstracted serial for RTT
static struct serial_ringbuffer _k64_int_rx; //UART send buffer area
struct k64_serial_device
{
/* UART base address */
UART_Type *baseAddress;
/* UART IRQ Number */
int irq_num;
/* device config */
struct serial_configure config;
};
//hardware abstract device
static struct k64_serial_device _k64_node =
{
(UART_Type *)UART0,
UART0_RX_TX_IRQn,
};
static rt_err_t _configure(struct rt_serial_device *serial, struct serial_configure *cfg)
{
unsigned int reg_C1 = 0,reg_C3 = 0,reg_C4 = 0,reg_BDH = 0,reg_BDL = 0,reg_S2 = 0,reg_BRFA=0;
unsigned int cal_SBR = 0;
UART_Type *uart_reg;
/* ref : drivers\system_MK60F12.c Line 64 ,BusClock = 60MHz
* calculate baud_rate
*/
uart_reg = ((struct k64_serial_device *)serial->parent.user_data)->baseAddress;
/*
* set bit order
*/
if (cfg->bit_order == BIT_ORDER_LSB)
reg_S2 &= ~(UART_S2_MSBF_MASK<<UART_S2_MSBF_SHIFT);
else if (cfg->bit_order == BIT_ORDER_MSB)
reg_S2 |= UART_S2_MSBF_MASK<<UART_S2_MSBF_SHIFT;
/*
* set data_bits
*/
if (cfg->data_bits == DATA_BITS_8)
reg_C1 &= ~(UART_C1_M_MASK<<UART_C1_M_SHIFT);
else if (cfg->data_bits == DATA_BITS_9)
reg_C1 |= UART_C1_M_MASK<<UART_C1_M_SHIFT;
/*
* set parity
*/
if (cfg->parity == PARITY_NONE)
{
reg_C1 &= ~(UART_C1_PE_MASK);
}
else
{
/* first ,set parity enable bit */
reg_C1 |= (UART_C1_PE_MASK);
/* second ,determine parity odd or even*/
if (cfg->parity == PARITY_ODD)
reg_C1 |= UART_C1_PT_MASK;
if (cfg->parity == PARITY_EVEN)
reg_C1 &= ~(UART_C1_PT_MASK);
}
/*
* set NZR mode
* not tested
*/
if (cfg->invert != NRZ_NORMAL)
{
/* not in normal mode ,set inverted polarity */
reg_C3 |= UART_C3_TXINV_MASK;
}
switch ((unsigned int)uart_reg)
{
/*
* if you're using other board
* set clock and pin map for UARTx
*/
case UART0_BASE:
/* calc SBR */
cal_SBR = SystemCoreClock / (16 * cfg->baud_rate);
/* check to see if sbr is out of range of register bits */
if ((cal_SBR > 0x1FFF) || (cal_SBR < 1))
{
/* unsupported baud rate for given source clock input*/
return -RT_ERROR;
}
/* calc baud_rate */
reg_BDH = (cal_SBR & 0x1FFF) >> 8 & 0x00FF;
reg_BDL = cal_SBR & 0x00FF;
/* fractional divider */
reg_BRFA = ((SystemCoreClock * 32) / (cfg->baud_rate * 16)) - (cal_SBR * 32);
reg_C4 = (unsigned char)(reg_BRFA & 0x001F);
SIM_SOPT5 &= ~ SIM_SOPT5_UART0RXSRC(0);
SIM_SOPT5 |= SIM_SOPT5_UART0RXSRC(0);
SIM_SOPT5 &= ~ SIM_SOPT5_UART0TXSRC(0);
SIM_SOPT5 |= SIM_SOPT5_UART0TXSRC(0);
// set UART0 clock
// Enable UART gate clocking
// Enable PORTE gate clocking
SIM_SCGC4 |= SIM_SCGC4_UART0_MASK;
SIM_SCGC5 |= SIM_SCGC5_PORTB_MASK;
// set UART0 pin
PORTB->PCR[16] &= ~(3UL << 8);
PORTB->PCR[16] |= (3UL << 8); // Pin mux configured as ALT3
PORTB->PCR[17] &= ~(3UL << 8);
PORTB->PCR[17] |= (3UL << 8); // Pin mux configured as ALT3
break;
default:
return -RT_ERROR;
}
uart_reg->BDH = reg_BDH;
uart_reg->BDL = reg_BDL;
uart_reg->C1 = reg_C1;
uart_reg->C4 = reg_C4;
uart_reg->S2 = reg_S2;
uart_reg->S2 = 0;
uart_reg->C3 = 0;
uart_reg->RWFIFO = UART_RWFIFO_RXWATER(1);
uart_reg->TWFIFO = UART_TWFIFO_TXWATER(0);
uart_reg->C2 = UART_C2_RE_MASK | //Receiver enable
UART_C2_TE_MASK; //Transmitter enable
return RT_EOK;
}
static rt_err_t _control(struct rt_serial_device *serial, int cmd, void *arg)
{
UART_Type *uart_reg;
int uart_irq_num = 0;
uart_reg = ((struct k64_serial_device *)serial->parent.user_data)->baseAddress;
uart_irq_num = ((struct k64_serial_device *)serial->parent.user_data)->irq_num;
switch (cmd)
{
case RT_DEVICE_CTRL_CLR_INT:
/* disable rx irq */
uart_reg->C2 &= ~UART_C2_RIE_MASK;
//disable NVIC
NVIC->ICER[uart_irq_num / 32] = 1 << (uart_irq_num % 32);
break;
case RT_DEVICE_CTRL_SET_INT:
/* enable rx irq */
uart_reg->C2 |= UART_C2_RIE_MASK;
//enable NVIC,we are sure uart's NVIC vector is in NVICICPR1
NVIC->ICPR[uart_irq_num / 32] = 1 << (uart_irq_num % 32);
NVIC->ISER[uart_irq_num / 32] = 1 << (uart_irq_num % 32);
break;
case RT_DEVICE_CTRL_SUSPEND:
/* suspend device */
uart_reg->C2 &= ~(UART_C2_RE_MASK | //Receiver enable
UART_C2_TE_MASK); //Transmitter enable
break;
case RT_DEVICE_CTRL_RESUME:
/* resume device */
uart_reg->C2 = UART_C2_RE_MASK | //Receiver enable
UART_C2_TE_MASK; //Transmitter enable
break;
}
return RT_EOK;
}
static int _putc(struct rt_serial_device *serial, char c)
{
UART_Type *uart_reg;
uart_reg = ((struct k64_serial_device *)serial->parent.user_data)->baseAddress;
while (!(uart_reg->S1 & UART_S1_TDRE_MASK));
uart_reg->D = (c & 0xFF);
return 1;
}
static int _getc(struct rt_serial_device *serial)
{
UART_Type *uart_reg;
uart_reg = ((struct k64_serial_device *)serial->parent.user_data)->baseAddress;
if (uart_reg->S1 & UART_S1_RDRF_MASK)
return (uart_reg->D);
else
return -1;
}
static const struct rt_uart_ops _k64_ops =
{
_configure,
_control,
_putc,
_getc,
};
void UART0_RX_TX_IRQHandler(void)
{
rt_interrupt_enter();
rt_hw_serial_isr((struct rt_serial_device*)&_k64_serial);
rt_interrupt_leave();
}
void rt_hw_uart_init(void)
{
struct serial_configure config;
/* fake configuration */
config.baud_rate = BAUD_RATE_115200;
config.bit_order = BIT_ORDER_LSB;
config.data_bits = DATA_BITS_8;
config.parity = PARITY_NONE;
config.stop_bits = STOP_BITS_1;
config.invert = NRZ_NORMAL;
_k64_serial.ops = &_k64_ops;
_k64_serial.int_rx = &_k64_int_rx;
_k64_serial.config = config;
rt_hw_serial_register(&_k64_serial, "uart0",
RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX | RT_DEVICE_FLAG_STREAM,
(void*)&_k64_node);
}
void rt_hw_console_output(const char *str)
{
while(*str != '\0')
{
if (*str == '\n')
_putc(&_k64_serial,'\r');
_putc(&_k64_serial,*str);
str++;
}
}
/*
* File : drv_uart.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2013, RT-Thread Develop Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://openlab.rt-thread.com/license/LICENSE
*
* Change Logs:
* Date Author Notes
*
*/
#ifndef DRV_UART_H
#define DRV_UART_H
#include <rthw.h>
#include <rtthread.h>
#include <rtdevice.h>
#include <MK64F12.H>
#include <drivers/serial.h>
void rt_hw_uart_init(void);
//for kernel debug when console not registered
void rt_hw_console_output(const char *str);
#endif /* end of include guard: DRV_UART_H */
/*
* File : led.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2009, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
*
* Change Logs:
* Date Author Notes
*
*/
#include <MK64F12.H>
#include "led.h"
const rt_uint32_t led_mask[] = {1 << 21, 1 << 22, 1 << 26};
void rt_hw_led_init(void)
{
SIM_SCGC5 |= (1 << SIM_SCGC5_PORTB_SHIFT);
SIM_SCGC5 |= (1 << SIM_SCGC5_PORTE_SHIFT);
PORTB->PCR[21] &= ~PORT_PCR_MUX_MASK;
PORTB->PCR[21] |= PORT_PCR_MUX(1); //PTB21 is GPIO pin
PORTB->PCR[22] &= ~PORT_PCR_MUX_MASK;
PORTB->PCR[22] |= PORT_PCR_MUX(1); //PTB22 is GPIO pin
PORTE->PCR[26] &= ~PORT_PCR_MUX_MASK;
PORTE->PCR[26] |= PORT_PCR_MUX(1); //PTE26 is GPIO pin
/* Switch LEDs off and enable output*/
PTB->PDDR |= GPIO_PDDR_PDD(led_mask[1] | led_mask[0]);
PTE->PDDR |= GPIO_PDDR_PDD(led_mask[2]);
rt_hw_led_off(LED_RED);
rt_hw_led_off(LED_GREEN);
rt_hw_led_off(LED_BLUE);
}
void rt_hw_led_uninit(void)
{
PORTB->PCR[21] &= ~PORT_PCR_MUX_MASK;
PORTB->PCR[22] &= ~PORT_PCR_MUX_MASK;
PORTE->PCR[26] &= ~PORT_PCR_MUX_MASK;
}
void rt_hw_led_on(rt_uint32_t n)
{
if (n != LED_GREEN)
{
PTB->PCOR |= led_mask[n];
}
else
{
PTE->PCOR |= led_mask[n];
}
}
void rt_hw_led_off(rt_uint32_t n)
{
if (n != LED_GREEN)
{
PTB->PSOR |= led_mask[n];
}
else
{
PTE->PSOR |= led_mask[n];
}
}
/*
* File : led.h
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2009, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
*
* Change Logs:
* Date Author Notes
*
*/
#ifndef __LED_H__
#define __LED_H__
#include <rtthread.h>
enum LED_NUM
{
LED_BLUE,
LED_RED,
LED_GREEN,
LED_MAX
};
void rt_hw_led_init(void);
void rt_hw_led_uninit(void);
void rt_hw_led_on(rt_uint32_t n);
void rt_hw_led_off(rt_uint32_t n);
#endif /* end of __LED_H__ */
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
/*
* Copyright (c) 2014, Freescale Semiconductor, Inc.
* All rights reserved.
*
* THIS SOFTWARE IS PROVIDED BY FREESCALE "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 FREESCALE 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.
*/
/*
* WARNING! DO NOT EDIT THIS FILE DIRECTLY!
*
* This file was generated automatically and any changes may be lost.
*/
#ifndef __HW_DMAMUX_REGISTERS_H__
#define __HW_DMAMUX_REGISTERS_H__
#include "regs.h"
/*
* MK64F12 DMAMUX
*
* DMA channel multiplexor
*
* Registers defined in this header file:
* - HW_DMAMUX_CHCFGn - Channel Configuration register
*
* - hw_dmamux_t - Struct containing all module registers.
*/
//! @name Module base addresses
//@{
#ifndef REGS_DMAMUX_BASE
#define HW_DMAMUX_INSTANCE_COUNT (1U) //!< Number of instances of the DMAMUX module.
#define HW_DMAMUX0 (0U) //!< Instance number for DMAMUX.
#define REGS_DMAMUX0_BASE (0x40021000U) //!< Base address for DMAMUX.
//! @brief Table of base addresses for DMAMUX instances.
static const uint32_t __g_regs_DMAMUX_base_addresses[] = {
REGS_DMAMUX0_BASE,
};
//! @brief Get the base address of DMAMUX by instance number.
//! @param x DMAMUX instance number, from 0 through 0.
#define REGS_DMAMUX_BASE(x) (__g_regs_DMAMUX_base_addresses[(x)])
//! @brief Get the instance number given a base address.
//! @param b Base address for an instance of DMAMUX.
#define REGS_DMAMUX_INSTANCE(b) ((b) == REGS_DMAMUX0_BASE ? HW_DMAMUX0 : 0)
#endif
//@}
//-------------------------------------------------------------------------------------------
// HW_DMAMUX_CHCFGn - Channel Configuration register
//-------------------------------------------------------------------------------------------
#ifndef __LANGUAGE_ASM__
/*!
* @brief HW_DMAMUX_CHCFGn - Channel Configuration register (RW)
*
* Reset value: 0x00U
*
* Each of the DMA channels can be independently enabled/disabled and associated
* with one of the DMA slots (peripheral slots or always-on slots) in the
* system. Setting multiple CHCFG registers with the same source value will result in
* unpredictable behavior. This is true, even if a channel is disabled (ENBL==0).
* Before changing the trigger or source settings, a DMA channel must be disabled
* via CHCFGn[ENBL].
*/
typedef union _hw_dmamux_chcfgn
{
uint8_t U;
struct _hw_dmamux_chcfgn_bitfields
{
uint8_t SOURCE : 6; //!< [5:0] DMA Channel Source (Slot)
uint8_t TRIG : 1; //!< [6] DMA Channel Trigger Enable
uint8_t ENBL : 1; //!< [7] DMA Channel Enable
} B;
} hw_dmamux_chcfgn_t;
#endif
/*!
* @name Constants and macros for entire DMAMUX_CHCFGn register
*/
//@{
#define HW_DMAMUX_CHCFGn_COUNT (16U)
#define HW_DMAMUX_CHCFGn_ADDR(x, n) (REGS_DMAMUX_BASE(x) + 0x0U + (0x1U * n))
#ifndef __LANGUAGE_ASM__
#define HW_DMAMUX_CHCFGn(x, n) (*(__IO hw_dmamux_chcfgn_t *) HW_DMAMUX_CHCFGn_ADDR(x, n))
#define HW_DMAMUX_CHCFGn_RD(x, n) (HW_DMAMUX_CHCFGn(x, n).U)
#define HW_DMAMUX_CHCFGn_WR(x, n, v) (HW_DMAMUX_CHCFGn(x, n).U = (v))
#define HW_DMAMUX_CHCFGn_SET(x, n, v) (HW_DMAMUX_CHCFGn_WR(x, n, HW_DMAMUX_CHCFGn_RD(x, n) | (v)))
#define HW_DMAMUX_CHCFGn_CLR(x, n, v) (HW_DMAMUX_CHCFGn_WR(x, n, HW_DMAMUX_CHCFGn_RD(x, n) & ~(v)))
#define HW_DMAMUX_CHCFGn_TOG(x, n, v) (HW_DMAMUX_CHCFGn_WR(x, n, HW_DMAMUX_CHCFGn_RD(x, n) ^ (v)))
#endif
//@}
/*
* Constants & macros for individual DMAMUX_CHCFGn bitfields
*/
/*!
* @name Register DMAMUX_CHCFGn, field SOURCE[5:0] (RW)
*
* Specifies which DMA source, if any, is routed to a particular DMA channel.
* See your device's chip configuration details for information about the
* peripherals and their slot numbers.
*/
//@{
#define BP_DMAMUX_CHCFGn_SOURCE (0U) //!< Bit position for DMAMUX_CHCFGn_SOURCE.
#define BM_DMAMUX_CHCFGn_SOURCE (0x3FU) //!< Bit mask for DMAMUX_CHCFGn_SOURCE.
#define BS_DMAMUX_CHCFGn_SOURCE (6U) //!< Bit field size in bits for DMAMUX_CHCFGn_SOURCE.
#ifndef __LANGUAGE_ASM__
//! @brief Read current value of the DMAMUX_CHCFGn_SOURCE field.
#define BR_DMAMUX_CHCFGn_SOURCE(x, n) (HW_DMAMUX_CHCFGn(x, n).B.SOURCE)
#endif
//! @brief Format value for bitfield DMAMUX_CHCFGn_SOURCE.
#define BF_DMAMUX_CHCFGn_SOURCE(v) (__REG_VALUE_TYPE((__REG_VALUE_TYPE((v), uint8_t) << BP_DMAMUX_CHCFGn_SOURCE), uint8_t) & BM_DMAMUX_CHCFGn_SOURCE)
#ifndef __LANGUAGE_ASM__
//! @brief Set the SOURCE field to a new value.
#define BW_DMAMUX_CHCFGn_SOURCE(x, n, v) (HW_DMAMUX_CHCFGn_WR(x, n, (HW_DMAMUX_CHCFGn_RD(x, n) & ~BM_DMAMUX_CHCFGn_SOURCE) | BF_DMAMUX_CHCFGn_SOURCE(v)))
#endif
//@}
/*!
* @name Register DMAMUX_CHCFGn, field TRIG[6] (RW)
*
* Enables the periodic trigger capability for the triggered DMA channel.
*
* Values:
* - 0 - Triggering is disabled. If triggering is disabled and ENBL is set, the
* DMA Channel will simply route the specified source to the DMA channel.
* (Normal mode)
* - 1 - Triggering is enabled. If triggering is enabled and ENBL is set, the
* DMAMUX is in Periodic Trigger mode.
*/
//@{
#define BP_DMAMUX_CHCFGn_TRIG (6U) //!< Bit position for DMAMUX_CHCFGn_TRIG.
#define BM_DMAMUX_CHCFGn_TRIG (0x40U) //!< Bit mask for DMAMUX_CHCFGn_TRIG.
#define BS_DMAMUX_CHCFGn_TRIG (1U) //!< Bit field size in bits for DMAMUX_CHCFGn_TRIG.
#ifndef __LANGUAGE_ASM__
//! @brief Read current value of the DMAMUX_CHCFGn_TRIG field.
#define BR_DMAMUX_CHCFGn_TRIG(x, n) (BITBAND_ACCESS8(HW_DMAMUX_CHCFGn_ADDR(x, n), BP_DMAMUX_CHCFGn_TRIG))
#endif
//! @brief Format value for bitfield DMAMUX_CHCFGn_TRIG.
#define BF_DMAMUX_CHCFGn_TRIG(v) (__REG_VALUE_TYPE((__REG_VALUE_TYPE((v), uint8_t) << BP_DMAMUX_CHCFGn_TRIG), uint8_t) & BM_DMAMUX_CHCFGn_TRIG)
#ifndef __LANGUAGE_ASM__
//! @brief Set the TRIG field to a new value.
#define BW_DMAMUX_CHCFGn_TRIG(x, n, v) (BITBAND_ACCESS8(HW_DMAMUX_CHCFGn_ADDR(x, n), BP_DMAMUX_CHCFGn_TRIG) = (v))
#endif
//@}
/*!
* @name Register DMAMUX_CHCFGn, field ENBL[7] (RW)
*
* Enables the DMA channel.
*
* Values:
* - 0 - DMA channel is disabled. This mode is primarily used during
* configuration of the DMAMux. The DMA has separate channel enables/disables, which
* should be used to disable or reconfigure a DMA channel.
* - 1 - DMA channel is enabled
*/
//@{
#define BP_DMAMUX_CHCFGn_ENBL (7U) //!< Bit position for DMAMUX_CHCFGn_ENBL.
#define BM_DMAMUX_CHCFGn_ENBL (0x80U) //!< Bit mask for DMAMUX_CHCFGn_ENBL.
#define BS_DMAMUX_CHCFGn_ENBL (1U) //!< Bit field size in bits for DMAMUX_CHCFGn_ENBL.
#ifndef __LANGUAGE_ASM__
//! @brief Read current value of the DMAMUX_CHCFGn_ENBL field.
#define BR_DMAMUX_CHCFGn_ENBL(x, n) (BITBAND_ACCESS8(HW_DMAMUX_CHCFGn_ADDR(x, n), BP_DMAMUX_CHCFGn_ENBL))
#endif
//! @brief Format value for bitfield DMAMUX_CHCFGn_ENBL.
#define BF_DMAMUX_CHCFGn_ENBL(v) (__REG_VALUE_TYPE((__REG_VALUE_TYPE((v), uint8_t) << BP_DMAMUX_CHCFGn_ENBL), uint8_t) & BM_DMAMUX_CHCFGn_ENBL)
#ifndef __LANGUAGE_ASM__
//! @brief Set the ENBL field to a new value.
#define BW_DMAMUX_CHCFGn_ENBL(x, n, v) (BITBAND_ACCESS8(HW_DMAMUX_CHCFGn_ADDR(x, n), BP_DMAMUX_CHCFGn_ENBL) = (v))
#endif
//@}
//-------------------------------------------------------------------------------------------
// hw_dmamux_t - module struct
//-------------------------------------------------------------------------------------------
/*!
* @brief All DMAMUX module registers.
*/
#ifndef __LANGUAGE_ASM__
#pragma pack(1)
typedef struct _hw_dmamux
{
__IO hw_dmamux_chcfgn_t CHCFGn[16]; //!< [0x0] Channel Configuration register
} hw_dmamux_t;
#pragma pack()
//! @brief Macro to access all DMAMUX registers.
//! @param x DMAMUX instance number.
//! @return Reference (not a pointer) to the registers struct. To get a pointer to the struct,
//! use the '&' operator, like <code>&HW_DMAMUX(0)</code>.
#define HW_DMAMUX(x) (*(hw_dmamux_t *) REGS_DMAMUX_BASE(x))
#endif
#endif // __HW_DMAMUX_REGISTERS_H__
// v22/130726/0.9
// EOF
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
import rtconfig
Import('RTT_ROOT')
from building import *
# get current directory
cwd = GetCurrentDir()
src = Glob('MK64F12/*.c')
#add for startup script
if rtconfig.CROSS_TOOL == 'gcc':
src = src + ['TOOLCHAIN_GCC_ARM/startup_MK64F12.S']
elif rtconfig.CROSS_TOOL == 'keil':
src = src + ['TOOLCHAIN_ARM_STD/startup_MK64F12.s']
# elif rtconfig.CROSS_TOOL == 'iar':
path = [cwd, cwd + '/MK64F12']
#CPPDEFINES = ['']
group = DefineGroup('Device', src, depend = [''], CPPPATH = path)
#CPPDEFINES = CPPDEFINES)
Return('group')
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册