diff --git a/bsp/stm32sky001/application.c b/bsp/stm32sky001/application.c new file mode 100644 index 0000000000000000000000000000000000000000..3c8f87d81336b65e125a686638416b8cf99f2d5c --- /dev/null +++ b/bsp/stm32sky001/application.c @@ -0,0 +1,27 @@ +/* + * 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 + * 2009-01-05 Bernard the first version + */ + +/** + * @addtogroup STM32 + */ +/*@{*/ + +#include + +int rt_application_init() +{ + return 0; +} + +/*@}*/ diff --git a/bsp/stm32sky001/board.c b/bsp/stm32sky001/board.c new file mode 100644 index 0000000000000000000000000000000000000000..fb245eeac9f321960e477896e4c98e0da9fa0186 --- /dev/null +++ b/bsp/stm32sky001/board.c @@ -0,0 +1,231 @@ +/* + * File : board.c + * This file is part of RT-Thread RTOS + * COPYRIGHT (C) 2006 - 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://openlab.rt-thread.com/license/LICENSE + * + * Change Logs: + * Date Author Notes + * 2006-08-23 Bernard first implementation + */ + +#include +#include + +#include "stm32f10x_lib.h" + +static void rt_hw_console_init(void); + +/** + * @addtogroup STM32SKY + */ + +/*@{*/ + +ErrorStatus HSEStartUpStatus; + +/******************************************************************************* + * Function Name : RCC_Configuration + * Description : Configures the different system clocks. + * Input : None + * Output : None + * Return : None + *******************************************************************************/ +void RCC_Configuration(void) +{ + /* RCC system reset(for debug purpose) */ + RCC_DeInit(); + + /* Enable HSE */ + RCC_HSEConfig(RCC_HSE_ON); + + /* Wait till HSE is ready */ + HSEStartUpStatus = RCC_WaitForHSEStartUp(); + + if(HSEStartUpStatus == SUCCESS) + { + /* HCLK = SYSCLK */ + RCC_HCLKConfig(RCC_SYSCLK_Div1); + + /* PCLK2 = HCLK */ + RCC_PCLK2Config(RCC_HCLK_Div1); + /* PCLK1 = HCLK/2 */ + RCC_PCLK1Config(RCC_HCLK_Div2); + + /* Flash 2 wait state */ + FLASH_SetLatency(FLASH_Latency_2); + /* Enable Prefetch Buffer */ + FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable); + + /* PLLCLK = 8MHz * 9 = 72 MHz */ + RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9); + + /* Enable PLL */ + RCC_PLLCmd(ENABLE); + + /* Wait till PLL is ready */ + while(RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET) ; + + /* Select PLL as system clock source */ + RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK); + + /* Wait till PLL is used as system clock source */ + while(RCC_GetSYSCLKSource() != 0x08) ; + } +} + +/******************************************************************************* +* Function Name : NVIC_Configuration +* Description : Configures Vector Table base location. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void NVIC_Configuration(void) +{ +#ifdef VECT_TAB_RAM + /* Set the Vector Table base location at 0x20000000 */ + NVIC_SetVectorTable(NVIC_VectTab_RAM, 0x0); +#else /* VECT_TAB_FLASH */ + /* Set the Vector Table base location at 0x08000000 */ + NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0); +#endif +} + +/******************************************************************************* + * Function Name : SysTick_Configuration + * Description : Configures the SysTick for OS tick. + * Input : None + * Output : None + * Return : None + *******************************************************************************/ +void SysTick_Configuration(void) +{ + RCC_ClocksTypeDef rcc_clocks; + rt_uint32_t cnts; + + RCC_GetClocksFreq(&rcc_clocks); + + cnts = (rt_uint32_t)rcc_clocks.HCLK_Frequency / RT_TICK_PER_SECOND; + + SysTick_SetReload(cnts); + SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK); + SysTick_CounterCmd(SysTick_Counter_Enable); + SysTick_ITConfig(ENABLE); +} + +extern void rt_hw_interrupt_thread_switch(void); +/** + * This is the timer interrupt service routine. + * + */ +void rt_hw_timer_handler(void) +{ + /* enter interrupt */ + rt_interrupt_enter(); + + rt_tick_increase(); + + /* leave interrupt */ + rt_interrupt_leave(); + rt_hw_interrupt_thread_switch(); +} + +/** + * This function will initial STM32 board. + */ +void rt_hw_board_init() +{ + /* Configure the system clocks */ + RCC_Configuration(); + + /* NVIC Configuration */ + NVIC_Configuration(); + + /* Configure the SysTick */ + SysTick_Configuration(); + + rt_hw_console_init(); +} + +/* init console to support rt_kprintf */ +static void rt_hw_console_init() +{ + /* Enable USART1 and GPIOA clocks */ + RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1 | RCC_APB2Periph_GPIOA, ENABLE); + + /* GPIO configuration */ + { + GPIO_InitTypeDef GPIO_InitStructure; + + /* Configure USART1 Tx (PA.09) as alternate function push-pull */ + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_Init(GPIOA, &GPIO_InitStructure); + + /* Configure USART1 Rx (PA.10) as input floating */ + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; + GPIO_Init(GPIOA, &GPIO_InitStructure); + } + + /* USART configuration */ + { + USART_InitTypeDef USART_InitStructure; + + /* USART1 configured as follow: + - BaudRate = 115200 baud + - Word Length = 8 Bits + - One Stop Bit + - No parity + - Hardware flow control disabled (RTS and CTS signals) + - Receive and transmit enabled + - USART Clock disabled + - USART CPOL: Clock is active low + - USART CPHA: Data is captured on the middle + - USART LastBit: The clock pulse of the last data bit is not output to + the SCLK pin + */ + USART_InitStructure.USART_BaudRate = 115200; + USART_InitStructure.USART_WordLength = USART_WordLength_8b; + USART_InitStructure.USART_StopBits = USART_StopBits_1; + USART_InitStructure.USART_Parity = USART_Parity_No; + USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None; + USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx; + USART_Init(USART1, &USART_InitStructure); + /* Enable USART1 */ + USART_Cmd(USART1, ENABLE); + } +} + +/* write one character to serial, must not trigger interrupt */ +static void rt_hw_console_putc(const char c) +{ + /* + to be polite with serial console add a line feed + to the carriage return character + */ + if (c=='\n')rt_hw_console_putc('\r'); + + while (!(USART1->SR & USART_FLAG_TXE)); + USART1->DR = (c & 0x1FF); +} + +/** + * This function is used by rt_kprintf to display a string on console. + * + * @param str the displayed string + */ +void rt_hw_console_output(const char* str) +{ + while (*str) + { + rt_hw_console_putc (*str++); + } +} + +/*@}*/ diff --git a/bsp/stm32sky001/board.h b/bsp/stm32sky001/board.h new file mode 100644 index 0000000000000000000000000000000000000000..b1be7c47ac0d3806880f377e8e3fdb70a305c042 --- /dev/null +++ b/bsp/stm32sky001/board.h @@ -0,0 +1,25 @@ +/* + * File : board.h + * 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 + * 2006-10-08 Bernard add board.h to this bsp + */ + +#ifndef __BOARD_H__ +#define __BOARD_H__ + +void rt_hw_board_led_on(int n); +void rt_hw_board_led_off(int n); +void rt_hw_board_init(void); + +void rt_hw_usart_init(void); +void rt_hw_sdcard_init(void); + +#endif diff --git a/bsp/stm32sky001/cortexm3_macro.s b/bsp/stm32sky001/cortexm3_macro.s new file mode 100644 index 0000000000000000000000000000000000000000..5984b58ef08ea55503276748ddd88eb83fea81aa --- /dev/null +++ b/bsp/stm32sky001/cortexm3_macro.s @@ -0,0 +1,279 @@ +;******************** (C) COPYRIGHT 2007 STMicroelectronics ******************** +;* File Name : cortexm3_macro.s +;* Author : MCD Application Team +;* Version : V1.1 +;* Date : 11/26/2007 +;* Description : Instruction wrappers for special Cortex-M3 instructions. +;******************************************************************************* +; THE PRESENT SOFTWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +; WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +; AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +; INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +; CONTENT OF SUCH SOFTWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +; INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +;******************************************************************************* + + THUMB + REQUIRE8 + PRESERVE8 + + AREA |.text|, CODE, READONLY, ALIGN=2 + + ; Exported functions + EXPORT __WFI + EXPORT __WFE + EXPORT __SEV + EXPORT __ISB + EXPORT __DSB + EXPORT __DMB + EXPORT __SVC + EXPORT __MRS_CONTROL + EXPORT __MSR_CONTROL + EXPORT __MRS_PSP + EXPORT __MSR_PSP + EXPORT __MRS_MSP + EXPORT __MSR_MSP + EXPORT __SETPRIMASK + EXPORT __RESETPRIMASK + EXPORT __SETFAULTMASK + EXPORT __RESETFAULTMASK + EXPORT __BASEPRICONFIG + EXPORT __GetBASEPRI + EXPORT __REV_HalfWord + EXPORT __REV_Word + +;******************************************************************************* +; Function Name : __WFI +; Description : Assembler function for the WFI instruction. +; Input : None +; Return : None +;******************************************************************************* +__WFI + + WFI + BX r14 + +;******************************************************************************* +; Function Name : __WFE +; Description : Assembler function for the WFE instruction. +; Input : None +; Return : None +;******************************************************************************* +__WFE + + WFE + BX r14 + +;******************************************************************************* +; Function Name : __SEV +; Description : Assembler function for the SEV instruction. +; Input : None +; Return : None +;******************************************************************************* +__SEV + + SEV + BX r14 + +;******************************************************************************* +; Function Name : __ISB +; Description : Assembler function for the ISB instruction. +; Input : None +; Return : None +;******************************************************************************* +__ISB + + ISB + BX r14 + +;******************************************************************************* +; Function Name : __DSB +; Description : Assembler function for the DSB instruction. +; Input : None +; Return : None +;******************************************************************************* +__DSB + + DSB + BX r14 + +;******************************************************************************* +; Function Name : __DMB +; Description : Assembler function for the DMB instruction. +; Input : None +; Return : None +;******************************************************************************* +__DMB + + DMB + BX r14 + +;******************************************************************************* +; Function Name : __SVC +; Description : Assembler function for the SVC instruction. +; Input : None +; Return : None +;******************************************************************************* +__SVC + + SVC 0x01 + BX r14 + +;******************************************************************************* +; Function Name : __MRS_CONTROL +; Description : Assembler function for the MRS instruction. +; Input : None +; Return : - r0 : Cortex-M3 CONTROL register value. +;******************************************************************************* +__MRS_CONTROL + + MRS r0, CONTROL + BX r14 + +;******************************************************************************* +; Function Name : __MSR_CONTROL +; Description : Assembler function for the MSR instruction. +; Input : - r0 : Cortex-M3 CONTROL register new value. +; Return : None +;******************************************************************************* +__MSR_CONTROL + + MSR CONTROL, r0 + ISB + BX r14 + +;******************************************************************************* +; Function Name : __MRS_PSP +; Description : Assembler function for the MRS instruction. +; Input : None +; Return : - r0 : Process Stack value. +;******************************************************************************* +__MRS_PSP + + MRS r0, PSP + BX r14 + +;******************************************************************************* +; Function Name : __MSR_PSP +; Description : Assembler function for the MSR instruction. +; Input : - r0 : Process Stack new value. +; Return : None +;******************************************************************************* +__MSR_PSP + + MSR PSP, r0 ; set Process Stack value + BX r14 + +;******************************************************************************* +; Function Name : __MRS_MSP +; Description : Assembler function for the MRS instruction. +; Input : None +; Return : - r0 : Main Stack value. +;******************************************************************************* +__MRS_MSP + + MRS r0, MSP + BX r14 + +;******************************************************************************* +; Function Name : __MSR_MSP +; Description : Assembler function for the MSR instruction. +; Input : - r0 : Main Stack new value. +; Return : None +;******************************************************************************* +__MSR_MSP + + MSR MSP, r0 ; set Main Stack value + BX r14 + +;******************************************************************************* +; Function Name : __SETPRIMASK +; Description : Assembler function to set the PRIMASK. +; Input : None +; Return : None +;******************************************************************************* +__SETPRIMASK + + CPSID i + BX r14 + +;******************************************************************************* +; Function Name : __RESETPRIMASK +; Description : Assembler function to reset the PRIMASK. +; Input : None +; Return : None +;******************************************************************************* +__RESETPRIMASK + + CPSIE i + BX r14 + +;******************************************************************************* +; Function Name : __SETFAULTMASK +; Description : Assembler function to set the FAULTMASK. +; Input : None +; Return : None +;******************************************************************************* +__SETFAULTMASK + + CPSID f + BX r14 + +;******************************************************************************* +; Function Name : __RESETFAULTMASK +; Description : Assembler function to reset the FAULTMASK. +; Input : None +; Return : None +;******************************************************************************* +__RESETFAULTMASK + + CPSIE f + BX r14 + +;******************************************************************************* +; Function Name : __BASEPRICONFIG +; Description : Assembler function to set the Base Priority. +; Input : - r0 : Base Priority new value +; Return : None +;******************************************************************************* +__BASEPRICONFIG + + MSR BASEPRI, r0 + BX r14 + +;******************************************************************************* +; Function Name : __GetBASEPRI +; Description : Assembler function to get the Base Priority value. +; Input : None +; Return : - r0 : Base Priority value +;******************************************************************************* +__GetBASEPRI + + MRS r0, BASEPRI_MAX + BX r14 + +;******************************************************************************* +; Function Name : __REV_HalfWord +; Description : Reverses the byte order in HalfWord(16-bit) input variable. +; Input : - r0 : specifies the input variable +; Return : - r0 : holds tve variable value after byte reversing. +;******************************************************************************* +__REV_HalfWord + + REV16 r0, r0 + BX r14 + +;******************************************************************************* +; Function Name : __REV_Word +; Description : Reverses the byte order in Word(32-bit) input variable. +; Input : - r0 : specifies the input variable +; Return : - r0 : holds tve variable value after byte reversing. +;******************************************************************************* +__REV_Word + + REV r0, r0 + BX r14 + + END + +;******************* (C) COPYRIGHT 2007 STMicroelectronics *****END OF FILE***** diff --git a/bsp/stm32sky001/enc28j60.c b/bsp/stm32sky001/enc28j60.c new file mode 100644 index 0000000000000000000000000000000000000000..841b740e9b66663ddd24cd378ac5746d3bcb37a6 --- /dev/null +++ b/bsp/stm32sky001/enc28j60.c @@ -0,0 +1,727 @@ +#include "enc28j60.h" + +#include +#include "lwipopts.h" +#include "stm32f10x_lib.h" + +#define MAX_ADDR_LEN 6 + +// #define CSACTIVE GPIO_ResetBits(GPIOB, GPIO_Pin_12); +// #define CSPASSIVE GPIO_SetBits(GPIOB, GPIO_Pin_12); +#define CSACTIVE GPIOB->BRR = GPIO_Pin_12; +#define CSPASSIVE GPIOB->BSRR = GPIO_Pin_12; + +struct net_device +{ + /* inherit from ethernet device */ + struct eth_device parent; + + /* interface address info. */ + rt_uint8_t dev_addr[MAX_ADDR_LEN]; /* hw address */ +}; + +static struct net_device enc28j60_dev_entry; +static struct net_device *enc28j60_dev =&enc28j60_dev_entry; +static rt_uint8_t Enc28j60Bank; +static rt_uint16_t NextPacketPtr; +static struct rt_semaphore tx_sem; + +void _delay_us(rt_uint32_t us) +{ + rt_uint32_t len; + for (;us > 0; us --) + for (len = 0; len < 20; len++ ); +} + +void delay_ms(rt_uint32_t ms) +{ + rt_uint32_t len; + for (;ms > 0; ms --) + for (len = 0; len < 100; len++ ); +} + +rt_uint8_t spi_read_op(rt_uint8_t op, rt_uint8_t address) +{ + int temp=0; + CSACTIVE; + + SPI_I2S_SendData(SPI2, (op | (address & ADDR_MASK))); + while(SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_BSY)==SET); + SPI_I2S_ReceiveData(SPI2); + SPI_I2S_SendData(SPI2, 0x00); + while(SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_BSY)==SET); + + // do dummy read if needed (for mac and mii, see datasheet page 29) + if(address & 0x80) + { + SPI_I2S_ReceiveData(SPI2); + SPI_I2S_SendData(SPI2, 0x00); + while(SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_BSY)==SET); + } + // release CS + + temp=SPI_I2S_ReceiveData(SPI2); + // for(t=0;t<20;t++); + CSPASSIVE; + return (temp); +} + +void spi_write_op(rt_uint8_t op, rt_uint8_t address, rt_uint8_t data) +{ + rt_uint32_t level; + + level = rt_hw_interrupt_disable(); + + CSACTIVE; + SPI_I2S_SendData(SPI2, op | (address & ADDR_MASK)); + while(SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_BSY)==SET); + SPI_I2S_SendData(SPI2,data); + while(SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_BSY)==SET); + CSPASSIVE; + + rt_hw_interrupt_enable(level); +} + +void enc28j60_set_bank(rt_uint8_t address) +{ + // set the bank (if needed) + if((address & BANK_MASK) != Enc28j60Bank) + { + // set the bank + spi_write_op(ENC28J60_BIT_FIELD_CLR, ECON1, (ECON1_BSEL1|ECON1_BSEL0)); + spi_write_op(ENC28J60_BIT_FIELD_SET, ECON1, (address & BANK_MASK)>>5); + Enc28j60Bank = (address & BANK_MASK); + } +} + +rt_uint8_t spi_read(rt_uint8_t address) +{ + // set the bank + enc28j60_set_bank(address); + // do the read + return spi_read_op(ENC28J60_READ_CTRL_REG, address); +} + +void spi_write(rt_uint8_t address, rt_uint8_t data) +{ + // set the bank + enc28j60_set_bank(address); + // do the write + spi_write_op(ENC28J60_WRITE_CTRL_REG, address, data); +} + +void enc28j60_phy_write(rt_uint8_t address, rt_uint16_t data) +{ + // set the PHY register address + spi_write(MIREGADR, address); + + // write the PHY data + spi_write(MIWRL, data); + spi_write(MIWRH, data>>8); + + // wait until the PHY write completes + while(spi_read(MISTAT) & MISTAT_BUSY) + { + _delay_us(15); + } +} + +// read upper 8 bits +rt_uint16_t enc28j60_phy_read(rt_uint8_t address) +{ + // Set the right address and start the register read operation + spi_write(MIREGADR, address); + spi_write(MICMD, MICMD_MIIRD); + + _delay_us(15); + + // wait until the PHY read completes + while(spi_read(MISTAT) & MISTAT_BUSY); + + // reset reading bit + spi_write(MICMD, 0x00); + + return (spi_read(MIRDH)); +} + +void enc28j60_clkout(rt_uint8_t clk) +{ + //setup clkout: 2 is 12.5MHz: + spi_write(ECOCON, clk & 0x7); +} + +/* + * Access the PHY to determine link status + */ +static void enc28j60_check_link_status() +{ + rt_uint16_t reg; + int duplex; + + reg = enc28j60_phy_read(PHSTAT2); + duplex = reg & PHSTAT2_DPXSTAT; + + if (reg & PHSTAT2_LSTAT) + { + /* on */ + } + else + { + /* off */ + } +} + +#ifdef RT_USING_FINSH +#include +/* + * Debug routine to dump useful register contents + */ +static void enc28j60(void) +{ + rt_kprintf("-- enc28j60 registers:\n"); + rt_kprintf("HwRevID: 0x%02x\n", spi_read(EREVID)); + rt_kprintf("Cntrl: ECON1 ECON2 ESTAT EIR EIE\n"); + rt_kprintf(" 0x%02x 0x%02x 0x%02x 0x%02x 0x%02x\n",spi_read(ECON1), spi_read(ECON2), spi_read(ESTAT), spi_read(EIR), spi_read(EIE)); + rt_kprintf("MAC : MACON1 MACON3 MACON4\n"); + rt_kprintf(" 0x%02x 0x%02x 0x%02x\n", spi_read(MACON1), spi_read(MACON3), spi_read(MACON4)); + rt_kprintf("Rx : ERXST ERXND ERXWRPT ERXRDPT ERXFCON EPKTCNT MAMXFL\n"); + rt_kprintf(" 0x%04x 0x%04x 0x%04x 0x%04x ", + (spi_read(ERXSTH) << 8) | spi_read(ERXSTL), + (spi_read(ERXNDH) << 8) | spi_read(ERXNDL), + (spi_read(ERXWRPTH) << 8) | spi_read(ERXWRPTL), + (spi_read(ERXRDPTH) << 8) | spi_read(ERXRDPTL)); + rt_kprintf("0x%02x 0x%02x 0x%04x\n", spi_read(ERXFCON), spi_read(EPKTCNT), + (spi_read(MAMXFLH) << 8) | spi_read(MAMXFLL)); + + rt_kprintf("Tx : ETXST ETXND MACLCON1 MACLCON2 MAPHSUP\n"); + rt_kprintf(" 0x%04x 0x%04x 0x%02x 0x%02x 0x%02x\n", + (spi_read(ETXSTH) << 8) | spi_read(ETXSTL), + (spi_read(ETXNDH) << 8) | spi_read(ETXNDL), + spi_read(MACLCON1), spi_read(MACLCON2), spi_read(MAPHSUP)); +} +FINSH_FUNCTION_EXPORT(enc28j60, dump enc28j60 registers) +#endif + +/* + * RX handler + * ignore PKTIF because is unreliable! (look at the errata datasheet) + * check EPKTCNT is the suggested workaround. + * We don't need to clear interrupt flag, automatically done when + * enc28j60_hw_rx() decrements the packet counter. + * Returns how many packet processed. + */ +void enc28j60_isr() +{ + /* Variable definitions can be made now. */ + volatile rt_uint32_t eir, pk_counter; + volatile rt_bool_t rx_activiated; + + rx_activiated = RT_FALSE; + + /* get EIR */ + eir = spi_read(EIR); + // rt_kprintf("eir: 0x%08x\n", eir); + + do + { + /* errata #4, PKTIF does not reliable */ + pk_counter = spi_read(EPKTCNT); + if (pk_counter) + { + rt_err_t result; + /* a frame has been received */ + result = eth_device_ready((struct eth_device*)&(enc28j60_dev->parent)); + RT_ASSERT(result == RT_EOK); + + // switch to bank 0 + enc28j60_set_bank(EIE); + // disable rx interrutps + spi_write_op(ENC28J60_BIT_FIELD_CLR, EIE, EIE_PKTIE); + } + + /* clear PKTIF */ + if (eir & EIR_PKTIF) + { + enc28j60_set_bank(EIR); + spi_write_op(ENC28J60_BIT_FIELD_CLR, EIR, EIR_PKTIF); + + rx_activiated = RT_TRUE; + } + + /* clear DMAIF */ + if (eir & EIR_DMAIF) + { + enc28j60_set_bank(EIR); + spi_write_op(ENC28J60_BIT_FIELD_CLR, EIR, EIR_DMAIF); + } + + /* LINK changed handler */ + if ( eir & EIR_LINKIF) + { + enc28j60_check_link_status(); + + /* read PHIR to clear the flag */ + enc28j60_phy_read(PHIR); + + enc28j60_set_bank(EIR); + spi_write_op(ENC28J60_BIT_FIELD_CLR, EIR, EIR_LINKIF); + } + + if (eir & EIR_TXIF) + { + /* A frame has been transmitted. */ + rt_sem_release(&tx_sem); + + enc28j60_set_bank(EIR); + spi_write_op(ENC28J60_BIT_FIELD_CLR, EIR, EIR_TXIF); + } + eir = spi_read(EIR); + // rt_kprintf("inner eir: 0x%08x\n", eir); + } while ((rx_activiated != RT_TRUE && eir != 0)); +} + +/* RT-Thread Device Interface */ + +/* initialize the interface */ +rt_err_t enc28j60_init(rt_device_t dev) +{ + CSPASSIVE; + + // perform system reset + spi_write_op(ENC28J60_SOFT_RESET, 0, ENC28J60_SOFT_RESET); + delay_ms(50); + NextPacketPtr = RXSTART_INIT; + + // Rx start + spi_write(ERXSTL, RXSTART_INIT&0xFF); + spi_write(ERXSTH, RXSTART_INIT>>8); + // set receive pointer address + spi_write(ERXRDPTL, RXSTOP_INIT&0xFF); + spi_write(ERXRDPTH, RXSTOP_INIT>>8); + // RX end + spi_write(ERXNDL, RXSTOP_INIT&0xFF); + spi_write(ERXNDH, RXSTOP_INIT>>8); + + // TX start + spi_write(ETXSTL, TXSTART_INIT&0xFF); + spi_write(ETXSTH, TXSTART_INIT>>8); + // set transmission pointer address + spi_write(EWRPTL, TXSTART_INIT&0xFF); + spi_write(EWRPTH, TXSTART_INIT>>8); + // TX end + spi_write(ETXNDL, TXSTOP_INIT&0xFF); + spi_write(ETXNDH, TXSTOP_INIT>>8); + + // do bank 1 stuff, packet filter: + // For broadcast packets we allow only ARP packtets + // All other packets should be unicast only for our mac (MAADR) + // + // The pattern to match on is therefore + // Type ETH.DST + // ARP BROADCAST + // 06 08 -- ff ff ff ff ff ff -> ip checksum for theses bytes=f7f9 + // in binary these poitions are:11 0000 0011 1111 + // This is hex 303F->EPMM0=0x3f,EPMM1=0x30 + spi_write(ERXFCON, ERXFCON_UCEN|ERXFCON_CRCEN|ERXFCON_BCEN); + + // do bank 2 stuff + // enable MAC receive + spi_write(MACON1, MACON1_MARXEN|MACON1_TXPAUS|MACON1_RXPAUS); + // enable automatic padding to 60bytes and CRC operations + // spi_write_op(ENC28J60_BIT_FIELD_SET, MACON3, MACON3_PADCFG0|MACON3_TXCRCEN|MACON3_FRMLNEN); + spi_write_op(ENC28J60_BIT_FIELD_SET, MACON3, MACON3_PADCFG0 | MACON3_TXCRCEN | MACON3_FRMLNEN | MACON3_FULDPX); + // bring MAC out of reset + + // set inter-frame gap (back-to-back) + // spi_write(MABBIPG, 0x12); + spi_write(MABBIPG, 0x15); + + spi_write(MACON4, MACON4_DEFER); + spi_write(MACLCON2, 63); + + // set inter-frame gap (non-back-to-back) + spi_write(MAIPGL, 0x12); + spi_write(MAIPGH, 0x0C); + + // Set the maximum packet size which the controller will accept + // Do not send packets longer than MAX_FRAMELEN: + spi_write(MAMXFLL, MAX_FRAMELEN&0xFF); + spi_write(MAMXFLH, MAX_FRAMELEN>>8); + + // do bank 3 stuff + // write MAC address + // NOTE: MAC address in ENC28J60 is byte-backward + spi_write(MAADR0, enc28j60_dev->dev_addr[5]); + spi_write(MAADR1, enc28j60_dev->dev_addr[4]); + spi_write(MAADR2, enc28j60_dev->dev_addr[3]); + spi_write(MAADR3, enc28j60_dev->dev_addr[2]); + spi_write(MAADR4, enc28j60_dev->dev_addr[1]); + spi_write(MAADR5, enc28j60_dev->dev_addr[0]); + + /* output off */ + spi_write(ECOCON, 0x00); + + // enc28j60_phy_write(PHCON1, 0x00); + enc28j60_phy_write(PHCON1, PHCON1_PDPXMD); // full duplex + // no loopback of transmitted frames + enc28j60_phy_write(PHCON2, PHCON2_HDLDIS); + + enc28j60_set_bank(ECON2); + spi_write_op(ENC28J60_BIT_FIELD_SET, ECON2, ECON2_AUTOINC); + + // switch to bank 0 + enc28j60_set_bank(ECON1); + // enable interrutps + spi_write_op(ENC28J60_BIT_FIELD_SET, EIE, EIE_INTIE|EIE_PKTIE|EIR_TXIF); + // enable packet reception + spi_write_op(ENC28J60_BIT_FIELD_SET, ECON1, ECON1_RXEN); + + /* clock out */ + // enc28j60_clkout(2); + + enc28j60_phy_write(PHLCON, 0xD76); //0x476 + delay_ms(20); + + rt_kprintf("enc28j60 init ok!\n"); + + return RT_EOK; +} + +/* control the interface */ +rt_err_t enc28j60_control(rt_device_t dev, rt_uint8_t cmd, void *args) +{ + switch(cmd) + { + case NIOCTL_GADDR: + /* get mac address */ + if(args) rt_memcpy(args, enc28j60_dev_entry.dev_addr, 6); + else return -RT_ERROR; + break; + + default : + break; + } + + return RT_EOK; +} + +/* Open the ethernet interface */ +rt_err_t enc28j60_open(rt_device_t dev, rt_uint16_t oflag) +{ + return RT_EOK; +} + +/* Close the interface */ +rt_err_t enc28j60_close(rt_device_t dev) +{ + return RT_EOK; +} + +/* Read */ +rt_size_t enc28j60_read(rt_device_t dev, rt_off_t pos, void* buffer, rt_size_t size) +{ + rt_set_errno(-RT_ENOSYS); + return 0; +} + +/* Write */ +rt_size_t enc28j60_write(rt_device_t dev, rt_off_t pos, const void* buffer, rt_size_t size) +{ + rt_set_errno(-RT_ENOSYS); + return 0; +} + +/* ethernet device interface */ +/* + * Transmit packet. + */ +rt_err_t enc28j60_tx( rt_device_t dev, struct pbuf* p) +{ + struct pbuf* q; + rt_uint32_t len; + rt_uint8_t* ptr; + + // rt_kprintf("tx pbuf: 0x%08x\n", p); + + /* lock tx operation */ + rt_sem_take(&tx_sem, RT_WAITING_FOREVER); + + // Set the write pointer to start of transmit buffer area + spi_write(EWRPTL, TXSTART_INIT&0xFF); + spi_write(EWRPTH, TXSTART_INIT>>8); + // Set the TXND pointer to correspond to the packet size given + spi_write(ETXNDL, (TXSTART_INIT+ p->tot_len + 1)&0xFF); + spi_write(ETXNDH, (TXSTART_INIT+ p->tot_len + 1)>>8); + + // write per-packet control byte (0x00 means use macon3 settings) + spi_write_op(ENC28J60_WRITE_BUF_MEM, 0, 0x00); + + for (q = p; q != NULL; q = q->next) + { + CSACTIVE; + + SPI_I2S_SendData(SPI2, ENC28J60_WRITE_BUF_MEM); + while(SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_BSY)==SET); + + len = q->len; + ptr = q->payload; + while(len) + { + SPI_I2S_SendData(SPI2,*ptr) ; + while(SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_BSY)==SET);; + ptr++; + + len--; + } + + CSPASSIVE; + } + + // send the contents of the transmit buffer onto the network + spi_write_op(ENC28J60_BIT_FIELD_SET, ECON1, ECON1_TXRTS); + // Reset the transmit logic problem. See Rev. B4 Silicon Errata point 12. + if( (spi_read(EIR) & EIR_TXERIF) ) + { + spi_write_op(ENC28J60_BIT_FIELD_CLR, ECON1, ECON1_TXRTS); + } + + // rt_kprintf("tx ok\n"); + + return RT_EOK; +} + +struct pbuf *enc28j60_rx(rt_device_t dev) +{ + struct pbuf* p; + rt_uint32_t len; + rt_uint16_t rxstat; + rt_uint32_t pk_counter; + + p = RT_NULL; + + pk_counter = spi_read(EPKTCNT); + if (pk_counter) + { + // Set the read pointer to the start of the received packet + spi_write(ERDPTL, (NextPacketPtr)); + spi_write(ERDPTH, (NextPacketPtr)>>8); + + // read the next packet pointer + NextPacketPtr = spi_read_op(ENC28J60_READ_BUF_MEM, 0); + NextPacketPtr |= spi_read_op(ENC28J60_READ_BUF_MEM, 0)<<8; + + // read the packet length (see datasheet page 43) + len = spi_read_op(ENC28J60_READ_BUF_MEM, 0); //0x54 + len |= spi_read_op(ENC28J60_READ_BUF_MEM, 0) <<8; //5554 + + len-=4; //remove the CRC count + + // read the receive status (see datasheet page 43) + rxstat = spi_read_op(ENC28J60_READ_BUF_MEM, 0); + rxstat |= ((rt_uint16_t)spi_read_op(ENC28J60_READ_BUF_MEM, 0))<<8; + + // check CRC and symbol errors (see datasheet page 44, table 7-3): + // The ERXFCON.CRCEN is set by default. Normally we should not + // need to check this. + if ((rxstat & 0x80)==0) + { + // invalid + len=0; + } + else + { + /* allocation pbuf */ + p = pbuf_alloc(PBUF_LINK, len, PBUF_RAM); + if (p != RT_NULL) + { + rt_uint8_t* data; + struct pbuf* q; + + for (q = p; q != RT_NULL; q= q->next) + { + data = q->payload; + len = q->len; + + CSACTIVE; + + SPI_I2S_SendData(SPI2,ENC28J60_READ_BUF_MEM); + while(SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_BSY)==SET); + + SPI_I2S_ReceiveData(SPI2); + + while(len) + { + len--; + SPI_I2S_SendData(SPI2,0x00) ; + while(SPI_I2S_GetFlagStatus(SPI2, SPI_I2S_FLAG_BSY)==SET); + + *data= SPI_I2S_ReceiveData(SPI2); + data++; + } + + CSPASSIVE; + } + } + } + + // Move the RX read pointer to the start of the next received packet + // This frees the memory we just read out + spi_write(ERXRDPTL, (NextPacketPtr)); + spi_write(ERXRDPTH, (NextPacketPtr)>>8); + + // decrement the packet counter indicate we are done with this packet + spi_write_op(ENC28J60_BIT_FIELD_SET, ECON2, ECON2_PKTDEC); + } + else + { + rt_uint32_t level; + /* lock enc28j60 */ + level = rt_hw_interrupt_disable(); + + // switch to bank 0 + enc28j60_set_bank(EIE); + // enable interrutps + spi_write_op(ENC28J60_BIT_FIELD_SET, EIE, EIE_PKTIE); + // switch to bank 0 + enc28j60_set_bank(ECON1); + // enable packet reception + spi_write_op(ENC28J60_BIT_FIELD_SET, ECON1, ECON1_RXEN); + + /* enable interrupt */ + rt_hw_interrupt_enable(level); + } + + return p; +} + +static void RCC_Configuration(void) +{ + /* enable spi2 clock */ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE); + + /* enable gpiob port clock */ + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB | RCC_APB2Periph_AFIO, ENABLE); +} + +static void NVIC_Configuration(void) +{ + NVIC_InitTypeDef NVIC_InitStructure; + + /* Configure one bit for preemption priority */ + NVIC_PriorityGroupConfig(NVIC_PriorityGroup_1); + + /* Enable the EXTI0 Interrupt */ + NVIC_InitStructure.NVIC_IRQChannel = EXTI0_IRQChannel; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); +} + +static void GPIO_Configuration() +{ + GPIO_InitTypeDef GPIO_InitStructure; + EXTI_InitTypeDef EXTI_InitStructure; + + /* configure PB0 as external interrupt */ + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; + GPIO_Init(GPIOB, &GPIO_InitStructure); + + /* Configure SPI2 pins: SCK, MISO and MOSI ----------------------------*/ + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13 | GPIO_Pin_14 | GPIO_Pin_15; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_10MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; + GPIO_Init(GPIOB, &GPIO_InitStructure); + + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; + GPIO_Init(GPIOB, &GPIO_InitStructure); + + /* Connect ENC28J60 EXTI Line to GPIOB Pin 0 */ + GPIO_EXTILineConfig(GPIO_PortSourceGPIOB, GPIO_PinSource0); + + /* Configure ENC28J60 EXTI Line to generate an interrupt on falling edge */ + EXTI_InitStructure.EXTI_Line = EXTI_Line0; + EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt; + EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Falling; + EXTI_InitStructure.EXTI_LineCmd = ENABLE; + EXTI_Init(&EXTI_InitStructure); + + /* Clear the Key Button EXTI line pending bit */ + EXTI_ClearITPendingBit(EXTI_Line0); +} + +static void SetupSPI (void) +{ + SPI_InitTypeDef SPI_InitStructure; + SPI_InitStructure.SPI_Direction = SPI_Direction_2Lines_FullDuplex; + SPI_InitStructure.SPI_Mode = SPI_Mode_Master; + SPI_InitStructure.SPI_DataSize = SPI_DataSize_8b; + SPI_InitStructure.SPI_CPOL = SPI_CPOL_Low; + SPI_InitStructure.SPI_CPHA = SPI_CPHA_1Edge; + SPI_InitStructure.SPI_NSS = SPI_NSS_Soft; + SPI_InitStructure.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_4; + SPI_InitStructure.SPI_FirstBit = SPI_FirstBit_MSB; + SPI_InitStructure.SPI_CRCPolynomial = 7; + SPI_Init(SPI2, &SPI_InitStructure); + SPI_Cmd(SPI2, ENABLE); +} + +static rt_timer_t enc28j60_timer; +void rt_hw_enc28j60_timeout(void* parameter) +{ + // switch to bank 0 + enc28j60_set_bank(EIE); + // enable interrutps + spi_write_op(ENC28J60_BIT_FIELD_SET, EIE, EIE_PKTIE); + // switch to bank 0 + enc28j60_set_bank(ECON1); + // enable packet reception + spi_write_op(ENC28J60_BIT_FIELD_SET, ECON1, ECON1_RXEN); + + enc28j60_isr(); +} + +int rt_hw_enc28j60_init() +{ + rt_err_t result; + + /* configuration PB5 as INT */ + RCC_Configuration(); + NVIC_Configuration(); + GPIO_Configuration(); + SetupSPI(); + + /* init rt-thread device interface */ + enc28j60_dev_entry.parent.parent.init = enc28j60_init; + enc28j60_dev_entry.parent.parent.open = enc28j60_open; + enc28j60_dev_entry.parent.parent.close = enc28j60_close; + enc28j60_dev_entry.parent.parent.read = enc28j60_read; + enc28j60_dev_entry.parent.parent.write = enc28j60_write; + enc28j60_dev_entry.parent.parent.control = enc28j60_control; + enc28j60_dev_entry.parent.eth_rx = enc28j60_rx; + enc28j60_dev_entry.parent.eth_tx = enc28j60_tx; + + /* Update MAC address */ + enc28j60_dev_entry.dev_addr[0] = 0x1e; + enc28j60_dev_entry.dev_addr[1] = 0x30; + enc28j60_dev_entry.dev_addr[2] = 0x6c; + enc28j60_dev_entry.dev_addr[3] = 0xa2; + enc28j60_dev_entry.dev_addr[4] = 0x45; + enc28j60_dev_entry.dev_addr[5] = 0x5e; + + rt_sem_init(&tx_sem, "emac", 1, RT_IPC_FLAG_FIFO); + + result = eth_device_init(&(enc28j60_dev->parent), "E0"); + + /* workaround for enc28j60 interrupt */ + enc28j60_timer = rt_timer_create("etimer", + rt_hw_enc28j60_timeout, RT_NULL, + 50, RT_TIMER_FLAG_PERIODIC); + if (enc28j60_timer != RT_NULL) + rt_timer_start(enc28j60_timer); + + return RT_EOK; +} diff --git a/bsp/stm32sky001/enc28j60.h b/bsp/stm32sky001/enc28j60.h new file mode 100644 index 0000000000000000000000000000000000000000..c8d27c2a5c187cb05ee15acae4655661e90ff563 --- /dev/null +++ b/bsp/stm32sky001/enc28j60.h @@ -0,0 +1,256 @@ +#ifndef __ENC28J60_H__ +#define __ENC28J60_H__ + +#include + +// ENC28J60 Control Registers +// Control register definitions are a combination of address, +// bank number, and Ethernet/MAC/PHY indicator bits. +// - Register address (bits 0-4) +// - Bank number (bits 5-6) +// - MAC/PHY indicator (bit 7) +#define ADDR_MASK 0x1F +#define BANK_MASK 0x60 +#define SPRD_MASK 0x80 +// All-bank registers +#define EIE 0x1B +#define EIR 0x1C +#define ESTAT 0x1D +#define ECON2 0x1E +#define ECON1 0x1F +// Bank 0 registers +#define ERDPTL (0x00|0x00) +#define ERDPTH (0x01|0x00) +#define EWRPTL (0x02|0x00) +#define EWRPTH (0x03|0x00) +#define ETXSTL (0x04|0x00) +#define ETXSTH (0x05|0x00) +#define ETXNDL (0x06|0x00) +#define ETXNDH (0x07|0x00) +#define ERXSTL (0x08|0x00) +#define ERXSTH (0x09|0x00) +#define ERXNDL (0x0A|0x00) +#define ERXNDH (0x0B|0x00) +#define ERXRDPTL (0x0C|0x00) +#define ERXRDPTH (0x0D|0x00) +#define ERXWRPTL (0x0E|0x00) +#define ERXWRPTH (0x0F|0x00) +#define EDMASTL (0x10|0x00) +#define EDMASTH (0x11|0x00) +#define EDMANDL (0x12|0x00) +#define EDMANDH (0x13|0x00) +#define EDMADSTL (0x14|0x00) +#define EDMADSTH (0x15|0x00) +#define EDMACSL (0x16|0x00) +#define EDMACSH (0x17|0x00) +// Bank 1 registers +#define EHT0 (0x00|0x20) +#define EHT1 (0x01|0x20) +#define EHT2 (0x02|0x20) +#define EHT3 (0x03|0x20) +#define EHT4 (0x04|0x20) +#define EHT5 (0x05|0x20) +#define EHT6 (0x06|0x20) +#define EHT7 (0x07|0x20) +#define EPMM0 (0x08|0x20) +#define EPMM1 (0x09|0x20) +#define EPMM2 (0x0A|0x20) +#define EPMM3 (0x0B|0x20) +#define EPMM4 (0x0C|0x20) +#define EPMM5 (0x0D|0x20) +#define EPMM6 (0x0E|0x20) +#define EPMM7 (0x0F|0x20) +#define EPMCSL (0x10|0x20) +#define EPMCSH (0x11|0x20) +#define EPMOL (0x14|0x20) +#define EPMOH (0x15|0x20) +#define EWOLIE (0x16|0x20) +#define EWOLIR (0x17|0x20) +#define ERXFCON (0x18|0x20) +#define EPKTCNT (0x19|0x20) +// Bank 2 registers +#define MACON1 (0x00|0x40|0x80) +#define MACON2 (0x01|0x40|0x80) +#define MACON3 (0x02|0x40|0x80) +#define MACON4 (0x03|0x40|0x80) +#define MABBIPG (0x04|0x40|0x80) +#define MAIPGL (0x06|0x40|0x80) +#define MAIPGH (0x07|0x40|0x80) +#define MACLCON1 (0x08|0x40|0x80) +#define MACLCON2 (0x09|0x40|0x80) +#define MAMXFLL (0x0A|0x40|0x80) +#define MAMXFLH (0x0B|0x40|0x80) +#define MAPHSUP (0x0D|0x40|0x80) +#define MICON (0x11|0x40|0x80) +#define MICMD (0x12|0x40|0x80) +#define MIREGADR (0x14|0x40|0x80) +#define MIWRL (0x16|0x40|0x80) +#define MIWRH (0x17|0x40|0x80) +#define MIRDL (0x18|0x40|0x80) +#define MIRDH (0x19|0x40|0x80) +// Bank 3 registers +#define MAADR1 (0x00|0x60|0x80) +#define MAADR0 (0x01|0x60|0x80) +#define MAADR3 (0x02|0x60|0x80) +#define MAADR2 (0x03|0x60|0x80) +#define MAADR5 (0x04|0x60|0x80) +#define MAADR4 (0x05|0x60|0x80) +#define EBSTSD (0x06|0x60) +#define EBSTCON (0x07|0x60) +#define EBSTCSL (0x08|0x60) +#define EBSTCSH (0x09|0x60) +#define MISTAT (0x0A|0x60|0x80) +#define EREVID (0x12|0x60) +#define ECOCON (0x15|0x60) +#define EFLOCON (0x17|0x60) +#define EPAUSL (0x18|0x60) +#define EPAUSH (0x19|0x60) +// PHY registers +#define PHCON1 0x00 +#define PHSTAT1 0x01 +#define PHHID1 0x02 +#define PHHID2 0x03 +#define PHCON2 0x10 +#define PHSTAT2 0x11 +#define PHIE 0x12 +#define PHIR 0x13 +#define PHLCON 0x14 + +// ENC28J60 ERXFCON Register Bit Definitions +#define ERXFCON_UCEN 0x80 +#define ERXFCON_ANDOR 0x40 +#define ERXFCON_CRCEN 0x20 +#define ERXFCON_PMEN 0x10 +#define ERXFCON_MPEN 0x08 +#define ERXFCON_HTEN 0x04 +#define ERXFCON_MCEN 0x02 +#define ERXFCON_BCEN 0x01 +// ENC28J60 EIE Register Bit Definitions +#define EIE_INTIE 0x80 +#define EIE_PKTIE 0x40 +#define EIE_DMAIE 0x20 +#define EIE_LINKIE 0x10 +#define EIE_TXIE 0x08 +#define EIE_WOLIE 0x04 +#define EIE_TXERIE 0x02 +#define EIE_RXERIE 0x01 +// ENC28J60 EIR Register Bit Definitions +#define EIR_PKTIF 0x40 +#define EIR_DMAIF 0x20 +#define EIR_LINKIF 0x10 +#define EIR_TXIF 0x08 +#define EIR_WOLIF 0x04 +#define EIR_TXERIF 0x02 +#define EIR_RXERIF 0x01 +// ENC28J60 ESTAT Register Bit Definitions +#define ESTAT_INT 0x80 +#define ESTAT_LATECOL 0x10 +#define ESTAT_RXBUSY 0x04 +#define ESTAT_TXABRT 0x02 +#define ESTAT_CLKRDY 0x01 +// ENC28J60 ECON2 Register Bit Definitions +#define ECON2_AUTOINC 0x80 +#define ECON2_PKTDEC 0x40 +#define ECON2_PWRSV 0x20 +#define ECON2_VRPS 0x08 +// ENC28J60 ECON1 Register Bit Definitions +#define ECON1_TXRST 0x80 +#define ECON1_RXRST 0x40 +#define ECON1_DMAST 0x20 +#define ECON1_CSUMEN 0x10 +#define ECON1_TXRTS 0x08 +#define ECON1_RXEN 0x04 +#define ECON1_BSEL1 0x02 +#define ECON1_BSEL0 0x01 +// ENC28J60 MACON1 Register Bit Definitions +#define MACON1_LOOPBK 0x10 +#define MACON1_TXPAUS 0x08 +#define MACON1_RXPAUS 0x04 +#define MACON1_PASSALL 0x02 +#define MACON1_MARXEN 0x01 +// ENC28J60 MACON2 Register Bit Definitions +#define MACON2_MARST 0x80 +#define MACON2_RNDRST 0x40 +#define MACON2_MARXRST 0x08 +#define MACON2_RFUNRST 0x04 +#define MACON2_MATXRST 0x02 +#define MACON2_TFUNRST 0x01 +// ENC28J60 MACON3 Register Bit Definitions +#define MACON3_PADCFG2 0x80 +#define MACON3_PADCFG1 0x40 +#define MACON3_PADCFG0 0x20 +#define MACON3_TXCRCEN 0x10 +#define MACON3_PHDRLEN 0x08 +#define MACON3_HFRMLEN 0x04 +#define MACON3_FRMLNEN 0x02 +#define MACON3_FULDPX 0x01 +// ENC28J60 MACON4 Register Bit Definitions +#define MACON4_DEFER (1<<6) +#define MACON4_BPEN (1<<5) +#define MACON4_NOBKOFF (1<<4) +// ENC28J60 MICMD Register Bit Definitions +#define MICMD_MIISCAN 0x02 +#define MICMD_MIIRD 0x01 +// ENC28J60 MISTAT Register Bit Definitions +#define MISTAT_NVALID 0x04 +#define MISTAT_SCAN 0x02 +#define MISTAT_BUSY 0x01 +// ENC28J60 PHY PHCON1 Register Bit Definitions +#define PHCON1_PRST 0x8000 +#define PHCON1_PLOOPBK 0x4000 +#define PHCON1_PPWRSV 0x0800 +#define PHCON1_PDPXMD 0x0100 +// ENC28J60 PHY PHSTAT1 Register Bit Definitions +#define PHSTAT1_PFDPX 0x1000 +#define PHSTAT1_PHDPX 0x0800 +#define PHSTAT1_LLSTAT 0x0004 +#define PHSTAT1_JBSTAT 0x0002 +/* ENC28J60 PHY PHSTAT2 Register Bit Definitions */ +#define PHSTAT2_TXSTAT (1 << 13) +#define PHSTAT2_RXSTAT (1 << 12) +#define PHSTAT2_COLSTAT (1 << 11) +#define PHSTAT2_LSTAT (1 << 10) +#define PHSTAT2_DPXSTAT (1 << 9) +#define PHSTAT2_PLRITY (1 << 5) +// ENC28J60 PHY PHCON2 Register Bit Definitions +#define PHCON2_FRCLINK 0x4000 +#define PHCON2_TXDIS 0x2000 +#define PHCON2_JABBER 0x0400 +#define PHCON2_HDLDIS 0x0100 + +// ENC28J60 Packet Control Byte Bit Definitions +#define PKTCTRL_PHUGEEN 0x08 +#define PKTCTRL_PPADEN 0x04 +#define PKTCTRL_PCRCEN 0x02 +#define PKTCTRL_POVERRIDE 0x01 + +// SPI operation codes +#define ENC28J60_READ_CTRL_REG 0x00 +#define ENC28J60_READ_BUF_MEM 0x3A +#define ENC28J60_WRITE_CTRL_REG 0x40 +#define ENC28J60_WRITE_BUF_MEM 0x7A +#define ENC28J60_BIT_FIELD_SET 0x80 +#define ENC28J60_BIT_FIELD_CLR 0xA0 +#define ENC28J60_SOFT_RESET 0xFF + +// The RXSTART_INIT should be zero. See Rev. B4 Silicon Errata +// buffer boundaries applied to internal 8K ram +// the entire available packet buffer space is allocated +// + +// start with recbuf at 0/ +#define RXSTART_INIT 0x0 +// receive buffer end +#define RXSTOP_INIT (0x1FFF-0x0600) - 1 +// start TX buffer at 0x1FFF-0x0600, pace for one full ethernet frame (~1500 bytes) + +#define TXSTART_INIT (0x1FFF-0x0600) +// stp TX buffer at end of mem +#define TXSTOP_INIT 0x1FFF + +// max frame length which the conroller will accept: +#define MAX_FRAMELEN 1518 + +int rt_hw_enc28j60_init(void); + +#endif diff --git a/bsp/stm32sky001/project.Uv2 b/bsp/stm32sky001/project.Uv2 new file mode 100644 index 0000000000000000000000000000000000000000..6b23e4e766f4009a41f907a320947b104ede49eb --- /dev/null +++ b/bsp/stm32sky001/project.Uv2 @@ -0,0 +1,170 @@ +### uVision2 Project, (C) Keil Software +### Do not modify ! + +Target (RT-Thread/STM32Sky), 0x0004 // Tools: 'ARM-ADS' + +Group (Startup) +Group (Library) +Group (Kernel) +Group (STM32) +Group (finsh) + +File 1,1,<.\application.c> +File 1,1,<.\board.c> +File 1,1,<.\startup.c> +File 1,2,<.\cortexm3_macro.s> +File 1,1,<.\stm32f10x_it.c> +File 1,5,<.\stm32f10x_conf.h> +File 1,5,<.\rtconfig.h> +File 1,1,<.\usart.c> +File 1,1,<.\rtc.c> +File 2,1,<.\library\src\stm32f10x_adc.c> +File 2,1,<.\library\src\stm32f10x_bkp.c> +File 2,1,<.\library\src\stm32f10x_can.c> +File 2,1,<.\library\src\stm32f10x_crc.c> +File 2,1,<.\library\src\stm32f10x_dac.c> +File 2,1,<.\library\src\stm32f10x_dbgmcu.c> +File 2,1,<.\library\src\stm32f10x_dma.c> +File 2,1,<.\library\src\stm32f10x_exti.c> +File 2,1,<.\library\src\stm32f10x_flash.c> +File 2,1,<.\library\src\stm32f10x_fsmc.c> +File 2,1,<.\library\src\stm32f10x_gpio.c> +File 2,1,<.\library\src\stm32f10x_i2c.c> +File 2,1,<.\library\src\stm32f10x_iwdg.c> +File 2,1,<.\library\src\stm32f10x_lib.c> +File 2,1,<.\library\src\stm32f10x_nvic.c> +File 2,1,<.\library\src\stm32f10x_pwr.c> +File 2,1,<.\library\src\stm32f10x_rcc.c> +File 2,1,<.\library\src\stm32f10x_rtc.c> +File 2,1,<.\library\src\stm32f10x_sdio.c> +File 2,1,<.\library\src\stm32f10x_spi.c> +File 2,1,<.\library\src\stm32f10x_systick.c> +File 2,1,<.\library\src\stm32f10x_tim.c> +File 2,1,<.\library\src\stm32f10x_usart.c> +File 2,1,<.\library\src\stm32f10x_wwdg.c> +File 3,1,<..\..\src\clock.c> +File 3,1,<..\..\src\idle.c> +File 3,1,<..\..\src\ipc.c> +File 3,1,<..\..\src\mem.c> +File 3,1,<..\..\src\mempool.c> +File 3,1,<..\..\src\object.c> +File 3,1,<..\..\src\scheduler.c> +File 3,1,<..\..\src\thread.c> +File 3,1,<..\..\src\timer.c> +File 3,1,<..\..\src\irq.c> +File 3,1,<..\..\src\kservice.c> +File 3,1,<..\..\src\device.c> +File 3,1,<..\..\src\slab.c> +File 4,1,<..\..\libcpu\arm\stm32\stack.c> +File 4,1,<..\..\libcpu\arm\stm32\interrupt.c> +File 4,1,<..\..\libcpu\arm\stm32\cpu.c> +File 4,1,<..\..\libcpu\arm\stm32\serial.c> +File 4,2,<..\..\libcpu\arm\stm32\context_rvds.S> +File 4,2,<..\..\libcpu\arm\stm32\start_rvds.s> +File 4,1,<..\..\libcpu\arm\stm32\fault.c> +File 4,2,<..\..\libcpu\arm\stm32\fault_rvds.S> +File 5,1,<..\..\finsh\finsh_compiler.c> +File 5,1,<..\..\finsh\finsh_error.c> +File 5,1,<..\..\finsh\finsh_heap.c> +File 5,1,<..\..\finsh\finsh_init.c> +File 5,1,<..\..\finsh\finsh_node.c> +File 5,1,<..\..\finsh\finsh_ops.c> +File 5,1,<..\..\finsh\finsh_parser.c> +File 5,1,<..\..\finsh\finsh_token.c> +File 5,1,<..\..\finsh\finsh_var.c> +File 5,1,<..\..\finsh\finsh_vm.c> +File 5,1,<..\..\finsh\shell.c> +File 5,1,<..\..\finsh\symbol.c> +File 5,1,<..\..\finsh\cmd.c> + + +Options 1,0,0 // Target 'RT-Thread/STM32Sky' + Device (STM32F103ZE) + Vendor (STMicroelectronics) + Cpu (IRAM(0x20000000-0x2000FFFF) IROM(0x8000000-0x807FFFF) CLOCK(8000000) CPUTYPE("Cortex-M3")) + FlashUt () + StupF ("STARTUP\ST\STM32F10x.s" ("STM32 Startup Code")) + FlashDR (UL2CM3(-O14 -S0 -C0 -N00("ARM Cortex-M3") -D00(1BA00477) -L00(4) -FO7 -FD20000000 -FC800 -FN1 -FF0STM32F10x_512 -FS08000000 -FL080000)) + DevID (4216) + Rgf (stm32f10x_lib.h) + Mem () + C () + A () + RL () + OH () + DBC_IFX () + DBC_CMS () + DBC_AMS () + DBC_LMS () + UseEnv=0 + EnvBin () + EnvInc () + EnvLib () + EnvReg (˙ST\STM32F10x\) + OrgReg (˙ST\STM32F10x\) + TgStat=16 + OutDir (.\obj\) + OutName (rtthread-stm32) + GenApp=1 + GenLib=0 + GenHex=1 + Debug=1 + Browse=1 + LstDir (.\obj\) + HexSel=1 + MG32K=0 + TGMORE=0 + RunUsr 0 0 <> + RunUsr 1 0 <> + BrunUsr 0 0 <> + BrunUsr 1 0 <> + CrunUsr 0 0 <> + CrunUsr 1 0 <> + SVCSID <> + GLFLAGS=1790 + ADSFLGA { 243,31,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 } + ACPUTYP ("Cortex-M3") + RVDEV () + ADSTFLGA { 0,12,0,2,99,0,1,66,0,0,0,0,0,0,0,0,0,0,0,0 } + OCMADSOCM { 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 } + OCMADSIRAM { 0,0,0,0,32,0,0,1,0 } + OCMADSIROM { 1,0,0,0,8,0,0,8,0 } + OCMADSXRAM { 0,0,0,0,0,0,0,0,0 } + OCR_RVCT { 1,0,0,0,0,0,0,0,0,1,0,0,0,0,0,0,0,0,1,0,0,0,0,0,0,0,0,1,0,0,0,8,0,0,8,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,32,0,0,1,0,0,0,0,0,0,0,0,0,0 } + RV_STAVEC () + ADSCCFLG { 5,0,0,4,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 } + ADSCMISC () + ADSCDEFN () + ADSCUDEF () + ADSCINCD (.;.\library\inc;.\library\src;..\..\include;..\..\libcpu\arm\stm32;..\..\finsh) + ADSASFLG { 1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 } + ADSAMISC () + ADSADEFN () + ADSAUDEF () + ADSAINCD () + PropFld { 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 } + IncBld=1 + AlwaysBuild=0 + GenAsm=0 + AsmAsm=0 + PublicsOnly=0 + StopCode=3 + CustArgs () + LibMods () + ADSLDFG { 17,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 } + ADSLDTA (0x08000000) + ADSLDDA (0x20000000) + ADSLDSC () + ADSLDIB () + ADSLDIC () + ADSLDMC (--keep __fsym_* --keep __vsym_*) + ADSLDIF () + ADSLDDW () + OPTDL (SARMCM3.DLL)()(DARMSTM.DLL)(-pSTM32F103ZE)(SARMCM3.DLL)()(TARMSTM.DLL)(-pSTM32F103ZE) + OPTDBG 48117,7,()()()()()()()()()() (Segger\JL2CM3.dll)()()() + FLASH1 { 9,0,0,0,1,0,0,0,5,16,0,0,0,0,0,0,0,0,0,0 } + FLASH2 (Segger\JLTAgdi.dll) + FLASH3 ("" ()) + FLASH4 () +EndOpt + diff --git a/bsp/stm32sky001/project.ewd b/bsp/stm32sky001/project.ewd new file mode 100644 index 0000000000000000000000000000000000000000..48f562856f9779cf1fa640c12e63b1bae8100b5a --- /dev/null +++ b/bsp/stm32sky001/project.ewd @@ -0,0 +1,1299 @@ + + + + 2 + + Debug + + ARM + + 1 + + C-SPY + 2 + + 18 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ARMSIM_ID + 2 + + 1 + 1 + 1 + + + + + + + + ANGEL_ID + 2 + + 0 + 1 + 1 + + + + + + + + + + + + GDBSERVER_ID + 2 + + 0 + 1 + 1 + + + + + + + + + + + IARROM_ID + 2 + + 0 + 1 + 1 + + + + + + + + + + JLINK_ID + 2 + + 10 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + LMIFTDI_ID + 2 + + 1 + 1 + 1 + + + + + + + + MACRAIGOR_ID + 2 + + 3 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + RDI_ID + 2 + + 1 + 1 + 1 + + + + + + + + + + + + + + + + + STLINK_ID + 2 + + 0 + 1 + 1 + + + + + THIRDPARTY_ID + 2 + + 0 + 1 + 1 + + + + + + + + + $TOOLKIT_DIR$\plugins\rtos\PowerPac\PowerPacRTOS.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-KA-CSpy.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\OSE\OseEpsilonPlugin.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\embOS\embOSPlugin.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\CMX\CmxArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\CMX\CmxTinyArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\ThreadX\ThreadXArmPlugin.ENU.ewplugin + 0 + + + $EW_DIR$\common\plugins\CodeCoverage\CodeCoverage.ENU.ewplugin + 1 + + + $EW_DIR$\common\plugins\Profiling\Profiling.ENU.ewplugin + 1 + + + $EW_DIR$\common\plugins\Orti\Orti.ENU.ewplugin + 0 + + + $EW_DIR$\common\plugins\Stack\Stack.ENU.ewplugin + 1 + + + $EW_DIR$\common\plugins\SymList\SymList.ENU.ewplugin + 1 + + + + + Release + + ARM + + 0 + + C-SPY + 2 + + 18 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ARMSIM_ID + 2 + + 1 + 1 + 0 + + + + + + + + ANGEL_ID + 2 + + 0 + 1 + 0 + + + + + + + + + + + + GDBSERVER_ID + 2 + + 0 + 1 + 0 + + + + + + + + + + + IARROM_ID + 2 + + 0 + 1 + 0 + + + + + + + + + + JLINK_ID + 2 + + 10 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + LMIFTDI_ID + 2 + + 1 + 1 + 0 + + + + + + + + MACRAIGOR_ID + 2 + + 3 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + RDI_ID + 2 + + 1 + 1 + 0 + + + + + + + + + + + + + + + + + STLINK_ID + 2 + + 0 + 1 + 0 + + + + + THIRDPARTY_ID + 2 + + 0 + 1 + 0 + + + + + + + + + $TOOLKIT_DIR$\plugins\rtos\PowerPac\PowerPacRTOS.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\uCOS-II\uCOS-II-KA-CSpy.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\OSE\OseEpsilonPlugin.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\embOS\embOSPlugin.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\CMX\CmxArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\CMX\CmxTinyArmPlugin.ENU.ewplugin + 0 + + + $TOOLKIT_DIR$\plugins\rtos\ThreadX\ThreadXArmPlugin.ENU.ewplugin + 0 + + + $EW_DIR$\common\plugins\CodeCoverage\CodeCoverage.ENU.ewplugin + 1 + + + $EW_DIR$\common\plugins\Profiling\Profiling.ENU.ewplugin + 1 + + + $EW_DIR$\common\plugins\Orti\Orti.ENU.ewplugin + 0 + + + $EW_DIR$\common\plugins\Stack\Stack.ENU.ewplugin + 1 + + + $EW_DIR$\common\plugins\SymList\SymList.ENU.ewplugin + 1 + + + + + + diff --git a/bsp/stm32sky001/project.ewp b/bsp/stm32sky001/project.ewp new file mode 100644 index 0000000000000000000000000000000000000000..274a87b87edaee157bc884bff52fde44ebd2a018 --- /dev/null +++ b/bsp/stm32sky001/project.ewp @@ -0,0 +1,1805 @@ + + + + 2 + + Debug + + ARM + + 1 + + General + 3 + + 17 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ICCARM + 2 + + 21 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + AARM + 2 + + 7 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + OBJCOPY + 0 + + 1 + 1 + 1 + + + + + + + + + CUSTOM + 3 + + + + + + + BICOMP + 0 + + + + BUILDACTION + 1 + + + + + + + ILINK + 0 + + 7 + 1 + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + IARCHIVE + 0 + + 0 + 1 + 1 + + + + + + + BILINK + 0 + + + + + Release + + ARM + + 0 + + General + 3 + + 17 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ICCARM + 2 + + 21 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + AARM + 2 + + 7 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + OBJCOPY + 0 + + 1 + 1 + 0 + + + + + + + + + CUSTOM + 3 + + + + + + + BICOMP + 0 + + + + BUILDACTION + 1 + + + + + + + ILINK + 0 + + 7 + 1 + 0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + IARCHIVE + 0 + + 0 + 1 + 0 + + + + + + + BILINK + 0 + + + + + finsh + + $PROJ_DIR$\..\..\finsh\cmd.c + + + $PROJ_DIR$\..\..\finsh\finsh_compiler.c + + + $PROJ_DIR$\..\..\finsh\finsh_error.c + + + $PROJ_DIR$\..\..\finsh\finsh_heap.c + + + $PROJ_DIR$\..\..\finsh\finsh_init.c + + + $PROJ_DIR$\..\..\finsh\finsh_node.c + + + $PROJ_DIR$\..\..\finsh\finsh_ops.c + + + $PROJ_DIR$\..\..\finsh\finsh_parser.c + + + $PROJ_DIR$\..\..\finsh\finsh_token.c + + + $PROJ_DIR$\..\..\finsh\finsh_var.c + + + $PROJ_DIR$\..\..\finsh\finsh_vm.c + + + $PROJ_DIR$\..\..\finsh\shell.c + + + $PROJ_DIR$\..\..\finsh\symbol.c + + + + Kernel + + $PROJ_DIR$\..\..\src\clock.c + + + $PROJ_DIR$\..\..\src\device.c + + + $PROJ_DIR$\..\..\src\idle.c + + + $PROJ_DIR$\..\..\src\ipc.c + + + $PROJ_DIR$\..\..\src\irq.c + + + $PROJ_DIR$\..\..\src\kservice.c + + + $PROJ_DIR$\..\..\src\mem.c + + + $PROJ_DIR$\..\..\src\mempool.c + + + $PROJ_DIR$\..\..\src\object.c + + + $PROJ_DIR$\..\..\src\scheduler.c + + + $PROJ_DIR$\..\..\src\slab.c + + + $PROJ_DIR$\..\..\src\thread.c + + + $PROJ_DIR$\..\..\src\timer.c + + + + Library + + $PROJ_DIR$\library\src\stm32f10x_adc.c + + + $PROJ_DIR$\library\src\stm32f10x_bkp.c + + + $PROJ_DIR$\library\src\stm32f10x_can.c + + + $PROJ_DIR$\library\src\stm32f10x_crc.c + + + $PROJ_DIR$\library\src\stm32f10x_dac.c + + + $PROJ_DIR$\library\src\stm32f10x_dbgmcu.c + + + $PROJ_DIR$\library\src\stm32f10x_dma.c + + + $PROJ_DIR$\library\src\stm32f10x_exti.c + + + $PROJ_DIR$\library\src\stm32f10x_flash.c + + + $PROJ_DIR$\library\src\stm32f10x_fsmc.c + + + $PROJ_DIR$\library\src\stm32f10x_gpio.c + + + $PROJ_DIR$\library\src\stm32f10x_i2c.c + + + $PROJ_DIR$\library\src\stm32f10x_iwdg.c + + + $PROJ_DIR$\library\src\stm32f10x_lib.c + + + $PROJ_DIR$\library\src\stm32f10x_nvic.c + + + $PROJ_DIR$\library\src\stm32f10x_pwr.c + + + $PROJ_DIR$\library\src\stm32f10x_rcc.c + + + $PROJ_DIR$\library\src\stm32f10x_rtc.c + + + $PROJ_DIR$\library\src\stm32f10x_sdio.c + + + $PROJ_DIR$\library\src\stm32f10x_spi.c + + + $PROJ_DIR$\library\src\stm32f10x_systick.c + + + $PROJ_DIR$\library\src\stm32f10x_tim.c + + + $PROJ_DIR$\library\src\stm32f10x_usart.c + + + $PROJ_DIR$\library\src\stm32f10x_wwdg.c + + + + Startup + + $PROJ_DIR$\application.c + + + $PROJ_DIR$\board.c + + + $PROJ_DIR$\rtconfig.h + + + $PROJ_DIR$\sdcard.c + + + $PROJ_DIR$\startup.c + + + $PROJ_DIR$\stm32f10x_it.c + + + $PROJ_DIR$\usart.c + + + + STM32 + + $PROJ_DIR$\..\..\libcpu\arm\stm32\context_iar.S + + + $PROJ_DIR$\..\..\libcpu\arm\stm32\cpu.c + + + $PROJ_DIR$\..\..\libcpu\arm\stm32\interrupt.c + + + $PROJ_DIR$\..\..\libcpu\arm\stm32\serial.c + + + $PROJ_DIR$\..\..\libcpu\arm\stm32\stack.c + + + $PROJ_DIR$\..\..\libcpu\arm\stm32\start_iar.c + + + + + diff --git a/bsp/stm32sky001/project.eww b/bsp/stm32sky001/project.eww new file mode 100644 index 0000000000000000000000000000000000000000..c2cb02eb1e89d73e24183274c1c886ddf74f9537 --- /dev/null +++ b/bsp/stm32sky001/project.eww @@ -0,0 +1,10 @@ + + + + + $WS_DIR$\project.ewp + + + + + diff --git a/bsp/stm32sky001/rtc.c b/bsp/stm32sky001/rtc.c new file mode 100644 index 0000000000000000000000000000000000000000..30adb4cf766f5a6ec330dbca8f0cf0f2a4b69b3f --- /dev/null +++ b/bsp/stm32sky001/rtc.c @@ -0,0 +1,217 @@ +#include +#include "stm32f10x_lib.h" + +static struct rt_device rtc; +static rt_err_t rt_rtc_open(rt_device_t dev, rt_uint16_t oflag) +{ + if (dev->rx_indicate != RT_NULL) + { + /* Open Interrupt */ + } + + return RT_EOK; +} + +static rt_size_t rt_rtc_read(rt_device_t dev, rt_off_t pos, void* buffer, rt_size_t size) +{ + return 0; +} + +static rt_err_t rt_rtc_control(rt_device_t dev, rt_uint8_t cmd, void *args) +{ + rt_time_t *time; + RT_ASSERT(dev != RT_NULL); + + switch (cmd) + { + case RT_DEVICE_CTRL_RTC_GET_TIME: + time = (rt_time_t *)args; + /* read device */ + *time = RTC_GetCounter(); + break; + + case RT_DEVICE_CTRL_RTC_SET_TIME: + { + time = (rt_time_t *)args; + + /* Enable PWR and BKP clocks */ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE); + + /* Allow access to BKP Domain */ + PWR_BackupAccessCmd(ENABLE); + + /* Wait until last write operation on RTC registers has finished */ + RTC_WaitForLastTask(); + + /* Change the current time */ + RTC_SetCounter(*time); + + /* Wait until last write operation on RTC registers has finished */ + RTC_WaitForLastTask(); + + BKP_WriteBackupRegister(BKP_DR1, 0xA5A5); + } + break; + } + + return RT_EOK; +} + +/******************************************************************************* +* Function Name : RTC_Configuration +* Description : Configures the RTC. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void RTC_Configuration(void) +{ + /* Enable PWR and BKP clocks */ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE); + + /* Allow access to BKP Domain */ + PWR_BackupAccessCmd(ENABLE); + + /* Reset Backup Domain */ + BKP_DeInit(); + + /* Enable LSE */ + RCC_LSEConfig(RCC_LSE_ON); + /* Wait till LSE is ready */ + while (RCC_GetFlagStatus(RCC_FLAG_LSERDY) == RESET) + { + } + + /* Select LSE as RTC Clock Source */ + RCC_RTCCLKConfig(RCC_RTCCLKSource_LSE); + + /* Enable RTC Clock */ + RCC_RTCCLKCmd(ENABLE); + + /* Wait for RTC registers synchronization */ + RTC_WaitForSynchro(); + + /* Wait until last write operation on RTC registers has finished */ + RTC_WaitForLastTask(); + + /* Set RTC prescaler: set RTC period to 1sec */ + RTC_SetPrescaler(32767); /* RTC period = RTCCLK/RTC_PR = (32.768 KHz)/(32767+1) */ + + /* Wait until last write operation on RTC registers has finished */ + RTC_WaitForLastTask(); +} + +void rt_hw_rtc_init(void) +{ + rtc.type = RT_Device_Class_RTC; + + if (BKP_ReadBackupRegister(BKP_DR1) != 0xA5A5) + { + rt_kprintf("rtc is not configured\n"); + rt_kprintf("please configure with set_date and set_time\n"); + RTC_Configuration(); + } + else + { + /* Wait for RTC registers synchronization */ + RTC_WaitForSynchro(); + } + + /* register rtc device */ + rtc.init = RT_NULL; + rtc.open = rt_rtc_open; + rtc.close = RT_NULL; + rtc.read = rt_rtc_read; + rtc.write = RT_NULL; + rtc.control = rt_rtc_control; + + /* no private */ + rtc.private = RT_NULL; + + rt_device_register(&rtc, "rtc", RT_DEVICE_FLAG_RDWR); + + return; +} + +#ifdef RT_USING_FINSH +#include +#include +time_t time(time_t* t) +{ + rt_device_t device; + time_t time; + + device = rt_device_find("rtc"); + if (device != RT_NULL) + { + rt_device_control(device, RT_DEVICE_CTRL_RTC_GET_TIME, &time); + if (t != RT_NULL) *t = time; + } + + return time; +} + +void set_date(rt_uint32_t year, rt_uint32_t month, rt_uint32_t day) +{ + time_t now; + struct tm* ti; + rt_device_t device; + + ti = RT_NULL; + /* get current time */ + time(&now); + + ti = localtime(&now); + if (ti != RT_NULL) + { + ti->tm_year = year - 1900; + ti->tm_mon = month; + ti->tm_mday = day; + } + + now = mktime(ti); + + device = rt_device_find("rtc"); + if (device != RT_NULL) + { + rt_rtc_control(device, RT_DEVICE_CTRL_RTC_SET_TIME, &now); + } +} +FINSH_FUNCTION_EXPORT(set_date, set date) + +void set_time(rt_uint32_t hour, rt_uint32_t minute, rt_uint32_t second) +{ + time_t now; + struct tm* ti; + rt_device_t device; + + ti = RT_NULL; + /* get current time */ + time(&now); + + ti = localtime(&now); + if (ti != RT_NULL) + { + ti->tm_hour = hour; + ti->tm_min = minute; + ti->tm_sec = second; + } + + now = mktime(ti); + device = rt_device_find("rtc"); + if (device != RT_NULL) + { + rt_rtc_control(device, RT_DEVICE_CTRL_RTC_SET_TIME, &now); + } +} +FINSH_FUNCTION_EXPORT(set_time, set second) + +void list_date() +{ + time_t now; + + time(&now); + rt_kprintf("%s\n", ctime(&now)); +} +FINSH_FUNCTION_EXPORT(list_date, set date) +#endif diff --git a/bsp/stm32sky001/rtc.h b/bsp/stm32sky001/rtc.h new file mode 100644 index 0000000000000000000000000000000000000000..29154aef9497e51cd555b8bec16d8c0f77712488 --- /dev/null +++ b/bsp/stm32sky001/rtc.h @@ -0,0 +1,6 @@ +#ifndef __RTC_H__ +#define __RTC_H__ + +void rt_hw_rtc_init(void); + +#endif diff --git a/bsp/stm32sky001/rtconfig.h b/bsp/stm32sky001/rtconfig.h new file mode 100644 index 0000000000000000000000000000000000000000..14195e10f17e5428100cb0d6c4aeda3876b69d1d --- /dev/null +++ b/bsp/stm32sky001/rtconfig.h @@ -0,0 +1,156 @@ +/* RT-Thread config file */ +#ifndef __RTTHREAD_CFG_H__ +#define __RTTHREAD_CFG_H__ + +/* RT_NAME_MAX*/ +#define RT_NAME_MAX 8 + +/* RT_ALIGN_SIZE*/ +#define RT_ALIGN_SIZE 4 + +/* PRIORITY_MAX*/ +#define RT_THREAD_PRIORITY_MAX 256 + +/* Tick per Second*/ +#define RT_TICK_PER_SECOND 100 + +/* SECTION: RT_DEBUG */ +/* Thread Debug*/ +#define RT_DEBUG +/* #define RT_THREAD_DEBUG */ +#define RT_USING_OVERFLOW_CHECK + +/* Using Hook*/ +#define RT_USING_HOOK + +/* SECTION: IPC */ +/* Using Semaphore*/ +#define RT_USING_SEMAPHORE + +/* Using Mutex*/ +#define RT_USING_MUTEX + +/* Using Event*/ +#define RT_USING_EVENT + +/* Using Faset Event*/ +/* #define RT_USING_FASTEVENT */ + +/* Using MailBox*/ +#define RT_USING_MAILBOX + +/* Using Message Queue*/ +#define RT_USING_MESSAGEQUEUE + +/* SECTION: Memory Management */ +/* Using Memory Pool Management*/ +#define RT_USING_MEMPOOL + +/* Using Dynamic Heap Management*/ +#define RT_USING_HEAP + +/* Using Small MM*/ +#define RT_USING_SMALL_MEM + +/* Using SLAB Allocator*/ +/* #define RT_USING_SLAB */ + +/* SECTION: Device System */ +/* Using Device System*/ +#define RT_USING_DEVICE +#define RT_USING_UART1 +// #define RT_USING_UART2 +// #define RT_USING_UART3 + +/* SECTION: Console options */ +/* the buffer size of console*/ +#define RT_CONSOLEBUF_SIZE 128 + +/* SECTION: FinSH shell options */ +/* Using FinSH as Shell*/ +#define RT_USING_FINSH +/* Using symbol table */ +#define FINSH_USING_SYMTAB +#define FINSH_USING_DESCRIPTION + +/* SECTION: a mini libc */ +/* Using mini libc library*/ +/* #define RT_USING_MINILIBC */ + +/* SECTION: C++ support */ +/* Using C++ support*/ +/* #define RT_USING_CPLUSPLUS */ + +/* #define RT_USING_RTGUI */ + +/* #define RT_USING_DFS */ +/* SECTION: DFS options */ +/* the max number of mounted filesystem */ +#define DFS_FILESYSTEMS_MAX 2 +/* the max number of opened files */ +#define DFS_FD_MAX 8 +/* the max number of cached sector */ +#define DFS_CACHE_MAX_NUM 8 + +/* SECTION: lwip, a lighwight TCP/IP protocol stack */ +/* Using lighweight TCP/IP protocol stack*/ +/* #define RT_USING_LWIP */ + +/* Trace LwIP protocol*/ +/* #define RT_LWIP_DEBUG */ + +/* Enable ICMP protocol*/ +#define RT_LWIP_ICMP + +/* Enable IGMP protocol*/ +/* #define RT_LWIP_IGMP */ + +/* Enable UDP protocol*/ +#define RT_LWIP_UDP + +/* Enable TCP protocol*/ +#define RT_LWIP_TCP + +/* the number of simulatenously active TCP connections*/ +#define RT_LWIP_TCP_PCB_NUM 5 + +/* TCP sender buffer space*/ +#define RT_LWIP_TCP_SND_BUF 1500 + +/* Enable SNMP protocol*/ +/* #define RT_LWIP_SNMP */ + +/* Using DHCP*/ +/* #define RT_LWIP_DHCP */ + +#define RT_LWIP_DNS + +/* ip address of target*/ +#define RT_LWIP_IPADDR0 192 +#define RT_LWIP_IPADDR1 168 +#define RT_LWIP_IPADDR2 1 +#define RT_LWIP_IPADDR3 30 + +/* gateway address of target*/ +#define RT_LWIP_GWADDR0 192 +#define RT_LWIP_GWADDR1 168 +#define RT_LWIP_GWADDR2 1 +#define RT_LWIP_GWADDR3 1 + +/* mask address of target*/ +#define RT_LWIP_MSKADDR0 255 +#define RT_LWIP_MSKADDR1 255 +#define RT_LWIP_MSKADDR2 255 +#define RT_LWIP_MSKADDR3 0 + +/* tcp thread options */ +#define RT_LWIP_TCPTHREAD_PRIORITY 120 +#define RT_LWIP_TCPTHREAD_MBOX_SIZE 4 +#define RT_LWIP_TCPTHREAD_STACKSIZE 1024 + +/* ethernet if thread options */ +#define RT_LWIP_ETHTHREAD_PRIORITY 128 +#define RT_LWIP_ETHTHREAD_MBOX_SIZE 4 +#define RT_LWIP_ETHTHREAD_STACKSIZE 512 + +#endif diff --git a/bsp/stm32sky001/startup.c b/bsp/stm32sky001/startup.c new file mode 100644 index 0000000000000000000000000000000000000000..e1caec079afd07abc8a1fcce6adf3584b407d5cf --- /dev/null +++ b/bsp/stm32sky001/startup.c @@ -0,0 +1,150 @@ +/* + * 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 + * 2006-08-31 Bernard first implementation + */ + +#include +#include + +#include "board.h" +#include "rtc.h" + +#ifdef RT_USING_LWIP +#include +#include "enc28j60.h" +#endif + +/** + * @addtogroup STM32 + */ + +/*@{*/ +#ifdef RT_USING_FINSH +extern void finsh_system_init(void); +extern void finsh_set_device(char* device); +#endif + +extern int rt_application_init(void); + +#ifdef __CC_ARM +extern int Image$$RW_IRAM1$$ZI$$Limit; +#elif __ICCARM__ +#pragma section="HEAP" +#else +extern int __bss_end; +#endif + +#ifdef DEBUG +/******************************************************************************* +* 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(u8* file, u32 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) ; +} +#endif + +/** + * 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(); + +#ifdef RT_USING_HEAP +#ifdef __CC_ARM + rt_system_heap_init((void*)&Image$$RW_IRAM1$$ZI$$Limit, (void*)0x20010000); +#elif __ICCARM__ + rt_system_heap_init(__segment_end("HEAP"), (void*)0x20010000); +#else + /* init memory system */ + rt_system_heap_init((void*)&__bss_end, (void*)0x20010000); +#endif +#endif + + /* init scheduler system */ + rt_system_scheduler_init(); + +#ifdef RT_USING_LWIP + eth_system_device_init(); + + /* register ethernetif device */ + rt_hw_enc28j60_init(); +#endif + + rt_hw_rtc_init(); + + /* init hardware serial device */ + rt_hw_usart_init(); +#ifdef RT_USING_DFS + rt_hw_sdcard_init(); +#endif + + /* init all device */ + rt_device_init_all(); + + /* init application */ + rt_application_init(); + +#ifdef RT_USING_FINSH + /* init finsh */ + finsh_system_init(); +#ifdef RT_USING_DEVICE + finsh_set_device("uart1"); +#endif +#endif + + /* init idle thread */ + rt_thread_idle_init(); + + /* start scheduler */ + rt_system_scheduler_start(); + + /* never reach here */ + return ; +} + +int main(void) +{ + rt_uint32_t UNUSED level; + + /* disable interrupt first */ + level = rt_hw_interrupt_disable(); + rtthread_startup(); + + return 0; +} + +/*@}*/ diff --git a/bsp/stm32sky001/stm32f10x_conf.h b/bsp/stm32sky001/stm32f10x_conf.h new file mode 100644 index 0000000000000000000000000000000000000000..f62bb06cd550e14cf263d4823d89701672a4ac34 --- /dev/null +++ b/bsp/stm32sky001/stm32f10x_conf.h @@ -0,0 +1,174 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ******************** +* File Name : stm32f10x_conf.h +* Author : MCD Application Team +* Version : V1.1.2 +* Date : 09/22/2008 +* Description : Library configuration file. +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_CONF_H +#define __STM32F10x_CONF_H + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_type.h" + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/* Uncomment the line below to compile the library in DEBUG mode, this will expanse + the "assert_param" macro in the firmware library code (see "Exported macro" + section below) */ +/* #define DEBUG 1*/ + +/* Comment the line below to disable the specific peripheral inclusion */ +/************************************* ADC ************************************/ +#define _ADC +#define _ADC1 +#define _ADC2 +#define _ADC3 + +/************************************* BKP ************************************/ +#define _BKP + +/************************************* CAN ************************************/ +#define _CAN + +/************************************* CRC ************************************/ +#define _CRC + +/************************************* DAC ************************************/ +#define _DAC + +/************************************* DBGMCU *********************************/ +#define _DBGMCU + +/************************************* DMA ************************************/ +#define _DMA +#define _DMA1_Channel1 +#define _DMA1_Channel2 +#define _DMA1_Channel3 +#define _DMA1_Channel4 +#define _DMA1_Channel5 +#define _DMA1_Channel6 +#define _DMA1_Channel7 +#define _DMA2_Channel1 +#define _DMA2_Channel2 +#define _DMA2_Channel3 +#define _DMA2_Channel4 +#define _DMA2_Channel5 + +/************************************* EXTI ***********************************/ +#define _EXTI + +/************************************* FLASH and Option Bytes *****************/ +#define _FLASH +/* Uncomment the line below to enable FLASH program/erase/protections functions, + otherwise only FLASH configuration (latency, prefetch, half cycle) functions + are enabled */ +/* #define _FLASH_PROG */ + +/************************************* FSMC ***********************************/ +#define _FSMC + +/************************************* GPIO ***********************************/ +#define _GPIO +#define _GPIOA +#define _GPIOB +#define _GPIOC +#define _GPIOD +#define _GPIOE +#define _GPIOF +#define _GPIOG +#define _AFIO + +/************************************* I2C ************************************/ +#define _I2C +#define _I2C1 +#define _I2C2 + +/************************************* IWDG ***********************************/ +#define _IWDG + +/************************************* NVIC ***********************************/ +#define _NVIC + +/************************************* PWR ************************************/ +#define _PWR + +/************************************* RCC ************************************/ +#define _RCC + +/************************************* RTC ************************************/ +#define _RTC + +/************************************* SDIO ***********************************/ +#define _SDIO + +/************************************* SPI ************************************/ +#define _SPI +#define _SPI1 +#define _SPI2 +#define _SPI3 + +/************************************* SysTick ********************************/ +#define _SysTick + +/************************************* TIM ************************************/ +#define _TIM +#define _TIM1 +#define _TIM2 +#define _TIM3 +#define _TIM4 +#define _TIM5 +#define _TIM6 +#define _TIM7 +#define _TIM8 + +/************************************* USART **********************************/ +#define _USART +#define _USART1 +#define _USART2 +#define _USART3 +#define _UART4 +#define _UART5 + +/************************************* WWDG ***********************************/ +#define _WWDG + +/* In the following line adjust the value of External High Speed oscillator (HSE) + used in your application */ +#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/ + +/* In the following line adjust the External High Speed oscillator (HSE) Startup + Timeout value */ +#define HSEStartUp_TimeOut ((u16)0x0500) /* Time out for HSE start up */ + +/* Exported macro ------------------------------------------------------------*/ +#ifdef DEBUG +/******************************************************************************* +* Macro Name : assert_param +* Description : The assert_param macro is used for function's parameters check. +* It is used only if the library is compiled in DEBUG mode. +* Input : - expr: If expr is false, it calls assert_failed function +* which reports the name of the source file and the source +* line number of the call that failed. +* If expr is true, it returns no value. +* Return : None +*******************************************************************************/ + #define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__)) +/* Exported functions ------------------------------------------------------- */ + void assert_failed(u8* file, u32 line); +#else + #define assert_param(expr) ((void)0) +#endif /* DEBUG */ + +#endif /* __STM32F10x_CONF_H */ + +/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/ diff --git a/bsp/stm32sky001/stm32f10x_flash.icf b/bsp/stm32sky001/stm32f10x_flash.icf new file mode 100644 index 0000000000000000000000000000000000000000..c32afef5fb2fa2731e1607c34324a100f90323e8 --- /dev/null +++ b/bsp/stm32sky001/stm32f10x_flash.icf @@ -0,0 +1,32 @@ +/*###ICF### Section handled by ICF editor, don't touch! ****/ +/*-Editor annotation file-*/ +/* IcfEditorFile="$TOOLKIT_DIR$\config\ide\IcfEditor\cortex_v1_0.xml" */ +/*-Specials-*/ +define symbol __ICFEDIT_intvec_start__ = 0x00000000; +/*-Memory Regions-*/ +define symbol __ICFEDIT_region_ROM_start__ = 0x00000000; +define symbol __ICFEDIT_region_ROM_end__ = 0x0007FFFF; +define symbol __ICFEDIT_region_RAM_start__ = 0x20000000; +define symbol __ICFEDIT_region_RAM_end__ = 0x2000FFFF; +/*-Sizes-*/ +define symbol __ICFEDIT_size_cstack__ = 0x200; +define symbol __ICFEDIT_size_heap__ = 0x000; +/**** End of ICF editor section. ###ICF###*/ + + +define memory mem with size = 4G; +define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__]; +define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__]; + +define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { }; +define block HEAP with alignment = 8, size = __ICFEDIT_size_heap__ { }; + +initialize by copy { readwrite }; +do not initialize { section .noinit }; + +keep { section FSymTab }; +keep { section VSymTab }; +place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec }; + +place in ROM_region { readonly }; +place in RAM_region { readwrite, block CSTACK, last block HEAP}; diff --git a/bsp/stm32sky001/stm32f10x_it.c b/bsp/stm32sky001/stm32f10x_it.c new file mode 100644 index 0000000000000000000000000000000000000000..bbb2307fe7ca783b5d08a7b3ce6bffe5534b5549 --- /dev/null +++ b/bsp/stm32sky001/stm32f10x_it.c @@ -0,0 +1,921 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ******************** +* File Name : stm32f10x_it.c +* Author : MCD Application Team +* Version : V1.1.2 +* Date : 09/22/2008 +* Description : Main Interrupt Service Routines. +* This file provides template for all exceptions handler +* and peripherals interrupt service routine. +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Includes ------------------------------------------------------------------*/ +#include +#include + +/* Private typedef -----------------------------------------------------------*/ +/* Private define ------------------------------------------------------------*/ +/* Private macro -------------------------------------------------------------*/ +/* Private variables ---------------------------------------------------------*/ +/* Private function prototypes -----------------------------------------------*/ +/* Private functions ---------------------------------------------------------*/ + +extern void rt_hw_timer_handler(void); +extern void rt_hw_interrupt_thread_switch(void); + +/******************************************************************************* +* Function Name : NMIException +* Description : This function handles NMI exception. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void NMIException(void) +{ +} + +/******************************************************************************* +* Function Name : HardFaultException +* Description : This function handles Hard Fault exception. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void HardFaultException(void) +{ + /* Go to infinite loop when Hard Fault exception occurs */ + rt_kprintf("hard fault exception\n"); + while (1) + { + } +} + +/******************************************************************************* +* Function Name : MemManageException +* Description : This function handles Memory Manage exception. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void MemManageException(void) +{ + /* Go to infinite loop when Memory Manage exception occurs */ + rt_kprintf("memory manage exception\n"); + while (1) + { + } +} + +/******************************************************************************* +* Function Name : BusFaultException +* Description : This function handles Bus Fault exception. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void BusFaultException(void) +{ + /* Go to infinite loop when Bus Fault exception occurs */ + rt_kprintf("bus fault exception\n"); + while (1) + { + } +} + +/******************************************************************************* +* Function Name : UsageFaultException +* Description : This function handles Usage Fault exception. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void UsageFaultException(void) +{ + /* Go to infinite loop when Usage Fault exception occurs */ + rt_kprintf("usage fault exception\n"); + while (1) + { + } +} + +/******************************************************************************* +* Function Name : DebugMonitor +* Description : This function handles Debug Monitor exception. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void DebugMonitor(void) +{ +} + +/******************************************************************************* +* Function Name : SVCHandler +* Description : This function handles SVCall exception. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void SVCHandler(void) +{ +} + +/******************************************************************************* +* Function Name : SysTickHandler +* Description : This function handles SysTick Handler. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void SysTickHandler(void) +{ + /* handle os tick */ + rt_hw_timer_handler(); +} + +/******************************************************************************* +* Function Name : WWDG_IRQHandler +* Description : This function handles WWDG interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void WWDG_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : PVD_IRQHandler +* Description : This function handles PVD interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void PVD_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : TAMPER_IRQHandler +* Description : This function handles Tamper interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void TAMPER_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : RTC_IRQHandler +* Description : This function handles RTC global interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void RTC_IRQHandler(void) +{ + if (RTC_GetITStatus(RTC_IT_SEC) != RESET) + { + /* Clear the RTC Second interrupt */ + RTC_ClearITPendingBit(RTC_IT_SEC); + + /* Wait until last write operation on RTC registers has finished */ + RTC_WaitForLastTask(); + + /* Reset RTC Counter when Time is 23:59:59 */ + if (RTC_GetCounter() == 0x00015180) + { + RTC_SetCounter(0x0); + /* Wait until last write operation on RTC registers has finished */ + RTC_WaitForLastTask(); + } + } +} + +/******************************************************************************* +* Function Name : FLASH_IRQHandler +* Description : This function handles Flash interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void FLASH_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : RCC_IRQHandler +* Description : This function handles RCC interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void RCC_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : EXTI0_IRQHandler +* Description : This function handles External interrupt Line 0 request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void EXTI0_IRQHandler(void) +{ +#ifdef RT_USING_LWIP + extern void enc28j60_isr(void); + + /* enter interrupt */ + rt_interrupt_enter(); + + enc28j60_isr(); + + /* Clear the Key Button EXTI line pending bit */ + EXTI_ClearITPendingBit(EXTI_Line0); + + /* leave interrupt */ + rt_interrupt_leave(); + rt_hw_interrupt_thread_switch(); +#endif +} + +/******************************************************************************* +* Function Name : EXTI1_IRQHandler +* Description : This function handles External interrupt Line 1 request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void EXTI1_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : EXTI2_IRQHandler +* Description : This function handles External interrupt Line 2 request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void EXTI2_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : EXTI3_IRQHandler +* Description : This function handles External interrupt Line 3 request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void EXTI3_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : EXTI4_IRQHandler +* Description : This function handles External interrupt Line 4 request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void EXTI4_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : DMA1_Channel1_IRQHandler +* Description : This function handles DMA1 Channel 1 interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void DMA1_Channel1_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : DMA1_Channel2_IRQHandler +* Description : This function handles DMA1 Channel 2 interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void DMA1_Channel2_IRQHandler(void) +{ +#ifdef RT_USING_UART3 + extern struct rt_device uart3_device; + + /* enter interrupt */ + rt_interrupt_enter(); + + if (DMA_GetITStatus(DMA1_IT_TC2)) + { + /* transmission complete, invoke serial dma tx isr */ + rt_hw_serial_dma_tx_isr(&uart3_device); + } + + /* clear DMA flag */ + DMA_ClearFlag(DMA1_FLAG_TC2 | DMA1_FLAG_TE2); + + /* leave interrupt */ + rt_interrupt_leave(); + rt_hw_interrupt_thread_switch(); +#endif +} + +/******************************************************************************* +* Function Name : DMA1_Channel3_IRQHandler +* Description : This function handles DMA1 Channel 3 interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void DMA1_Channel3_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : DMA1_Channel4_IRQHandler +* Description : This function handles DMA1 Channel 4 interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void DMA1_Channel4_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : DMA1_Channel5_IRQHandler +* Description : This function handles DMA1 Channel 5 interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void DMA1_Channel5_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : DMA1_Channel6_IRQHandler +* Description : This function handles DMA1 Channel 6 interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void DMA1_Channel6_IRQHandler(void) +{ +#ifdef RT_USING_UART2 + extern struct rt_device uart2_device; + + /* enter interrupt */ + rt_interrupt_enter(); + + /* clear DMA flag */ + DMA_ClearFlag(DMA1_FLAG_TC6 | DMA1_FLAG_TE6); + rt_hw_serial_dma_rx_isr(&uart2_device); + + /* leave interrupt */ + rt_interrupt_leave(); + rt_hw_interrupt_thread_switch(); +#endif +} + +/******************************************************************************* +* Function Name : DMA1_Channel7_IRQHandler +* Description : This function handles DMA1 Channel 7 interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void DMA1_Channel7_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : ADC1_2_IRQHandler +* Description : This function handles ADC1 and ADC2 global interrupts requests. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void ADC1_2_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : USB_HP_CAN_TX_IRQHandler +* Description : This function handles USB High Priority or CAN TX interrupts +* requests. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void USB_HP_CAN_TX_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : USB_LP_CAN_RX0_IRQHandler +* Description : This function handles USB Low Priority or CAN RX0 interrupts +* requests. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void USB_LP_CAN_RX0_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : CAN_RX1_IRQHandler +* Description : This function handles CAN RX1 interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void CAN_RX1_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : CAN_SCE_IRQHandler +* Description : This function handles CAN SCE interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void CAN_SCE_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : EXTI9_5_IRQHandler +* Description : This function handles External lines 9 to 5 interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void EXTI9_5_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : TIM1_BRK_IRQHandler +* Description : This function handles TIM1 Break interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void TIM1_BRK_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : TIM1_UP_IRQHandler +* Description : This function handles TIM1 overflow and update interrupt +* request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void TIM1_UP_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : TIM1_TRG_COM_IRQHandler +* Description : This function handles TIM1 Trigger and commutation interrupts +* requests. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void TIM1_TRG_COM_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : TIM1_CC_IRQHandler +* Description : This function handles TIM1 capture compare interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void TIM1_CC_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : TIM2_IRQHandler +* Description : This function handles TIM2 global interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void TIM2_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : TIM3_IRQHandler +* Description : This function handles TIM3 global interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void TIM3_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : TIM4_IRQHandler +* Description : This function handles TIM4 global interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void TIM4_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : I2C1_EV_IRQHandler +* Description : This function handles I2C1 Event interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void I2C1_EV_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : I2C1_ER_IRQHandler +* Description : This function handles I2C1 Error interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void I2C1_ER_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : I2C2_EV_IRQHandler +* Description : This function handles I2C2 Event interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void I2C2_EV_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : I2C2_ER_IRQHandler +* Description : This function handles I2C2 Error interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void I2C2_ER_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : SPI1_IRQHandler +* Description : This function handles SPI1 global interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void SPI1_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : SPI2_IRQHandler +* Description : This function handles SPI2 global interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void SPI2_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : USART1_IRQHandler +* Description : This function handles USART1 global interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void USART1_IRQHandler(void) +{ +#ifdef RT_USING_UART1 + extern struct rt_device uart1_device; + /* enter interrupt */ + rt_interrupt_enter(); + + rt_hw_serial_isr(&uart1_device); + + /* leave interrupt */ + rt_interrupt_leave(); + rt_hw_interrupt_thread_switch(); +#endif +} + +/******************************************************************************* +* Function Name : USART2_IRQHandler +* Description : This function handles USART2 global interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void USART2_IRQHandler(void) +{ +#ifdef RT_USING_UART2 + extern struct rt_device uart2_device; + + /* enter interrupt */ + rt_interrupt_enter(); + + rt_hw_serial_isr(&uart2_device); + + /* leave interrupt */ + rt_interrupt_leave(); + rt_hw_interrupt_thread_switch(); +#endif +} + +/******************************************************************************* +* Function Name : USART3_IRQHandler +* Description : This function handles USART3 global interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void USART3_IRQHandler(void) +{ +#ifdef RT_USING_UART3 + extern struct rt_device uart3_device; + + /* enter interrupt */ + rt_interrupt_enter(); + + rt_hw_serial_isr(&uart3_device); + + /* leave interrupt */ + rt_interrupt_leave(); + rt_hw_interrupt_thread_switch(); +#endif +} + +/******************************************************************************* +* Function Name : EXTI15_10_IRQHandler +* Description : This function handles External lines 15 to 10 interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void EXTI15_10_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : RTCAlarm_IRQHandler +* Description : This function handles RTC Alarm interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void RTCAlarm_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : USBWakeUp_IRQHandler +* Description : This function handles USB WakeUp interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void USBWakeUp_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : TIM8_BRK_IRQHandler +* Description : This function handles TIM8 Break interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void TIM8_BRK_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : TIM8_UP_IRQHandler +* Description : This function handles TIM8 overflow and update interrupt +* request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void TIM8_UP_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : TIM8_TRG_COM_IRQHandler +* Description : This function handles TIM8 Trigger and commutation interrupts +* requests. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void TIM8_TRG_COM_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : TIM8_CC_IRQHandler +* Description : This function handles TIM8 capture compare interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void TIM8_CC_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : ADC3_IRQHandler +* Description : This function handles ADC3 global interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void ADC3_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : FSMC_IRQHandler +* Description : This function handles FSMC global interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void FSMC_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : SDIO_IRQHandler +* Description : This function handles SDIO global interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void SDIO_IRQHandler(void) +{ +#ifdef RT_USING_DFS + extern int SD_ProcessIRQSrc(void); + + /* enter interrupt */ + rt_interrupt_enter(); + + /* Process All SDIO Interrupt Sources */ + SD_ProcessIRQSrc(); + + /* leave interrupt */ + rt_interrupt_leave(); + rt_hw_interrupt_thread_switch(); +#endif +} + +/******************************************************************************* +* Function Name : TIM5_IRQHandler +* Description : This function handles TIM5 global interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void TIM5_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : SPI3_IRQHandler +* Description : This function handles SPI3 global interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void SPI3_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : UART4_IRQHandler +* Description : This function handles UART4 global interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void UART4_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : UART5_IRQHandler +* Description : This function handles UART5 global interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void UART5_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : TIM6_IRQHandler +* Description : This function handles TIM6 global interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void TIM6_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : TIM7_IRQHandler +* Description : This function handles TIM7 global interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void TIM7_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : DMA2_Channel1_IRQHandler +* Description : This function handles DMA2 Channel 1 interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void DMA2_Channel1_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : DMA2_Channel2_IRQHandler +* Description : This function handles DMA2 Channel 2 interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void DMA2_Channel2_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : DMA2_Channel3_IRQHandler +* Description : This function handles DMA2 Channel 3 interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void DMA2_Channel3_IRQHandler(void) +{ +} + +/******************************************************************************* +* Function Name : DMA2_Channel4_5_IRQHandler +* Description : This function handles DMA2 Channel 4 and DMA2 Channel 5 +* interrupt request. +* Input : None +* Output : None +* Return : None +*******************************************************************************/ +void DMA2_Channel4_5_IRQHandler(void) +{ +} + +/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/ diff --git a/bsp/stm32sky001/stm32f10x_it.h b/bsp/stm32sky001/stm32f10x_it.h new file mode 100644 index 0000000000000000000000000000000000000000..11740669fadfae3d90385afa7958c371172fd2e1 --- /dev/null +++ b/bsp/stm32sky001/stm32f10x_it.h @@ -0,0 +1,100 @@ +/******************** (C) COPYRIGHT 2008 STMicroelectronics ******************** +* File Name : stm32f10x_it.h +* Author : MCD Application Team +* Version : V2.0.3 +* Date : 09/22/2008 +* Description : This file contains the headers of the interrupt handlers. +******************************************************************************** +* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS +* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. +* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, +* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE +* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING +* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. +*******************************************************************************/ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __STM32F10x_IT_H +#define __STM32F10x_IT_H + +/* Includes ------------------------------------------------------------------*/ +#include "stm32f10x_lib.h" + +/* Exported types ------------------------------------------------------------*/ +/* Exported constants --------------------------------------------------------*/ +/* Exported macro ------------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ + +void NMIException(void); +void HardFaultException(void); +void MemManageException(void); +void BusFaultException(void); +void UsageFaultException(void); +void DebugMonitor(void); +void SVCHandler(void); +void rt_hw_pend_sv(void); +void SysTickHandler(void); +void WWDG_IRQHandler(void); +void PVD_IRQHandler(void); +void TAMPER_IRQHandler(void); +void RTC_IRQHandler(void); +void FLASH_IRQHandler(void); +void RCC_IRQHandler(void); +void EXTI0_IRQHandler(void); +void EXTI1_IRQHandler(void); +void EXTI2_IRQHandler(void); +void EXTI3_IRQHandler(void); +void EXTI4_IRQHandler(void); +void DMA1_Channel1_IRQHandler(void); +void DMA1_Channel2_IRQHandler(void); +void DMA1_Channel3_IRQHandler(void); +void DMA1_Channel4_IRQHandler(void); +void DMA1_Channel5_IRQHandler(void); +void DMA1_Channel6_IRQHandler(void); +void DMA1_Channel7_IRQHandler(void); +void ADC1_2_IRQHandler(void); +void USB_HP_CAN_TX_IRQHandler(void); +void USB_LP_CAN_RX0_IRQHandler(void); +void CAN_RX1_IRQHandler(void); +void CAN_SCE_IRQHandler(void); +void EXTI9_5_IRQHandler(void); +void TIM1_BRK_IRQHandler(void); +void TIM1_UP_IRQHandler(void); +void TIM1_TRG_COM_IRQHandler(void); +void TIM1_CC_IRQHandler(void); +void TIM2_IRQHandler(void); +void TIM3_IRQHandler(void); +void TIM4_IRQHandler(void); +void I2C1_EV_IRQHandler(void); +void I2C1_ER_IRQHandler(void); +void I2C2_EV_IRQHandler(void); +void I2C2_ER_IRQHandler(void); +void SPI1_IRQHandler(void); +void SPI2_IRQHandler(void); +void USART1_IRQHandler(void); +void USART2_IRQHandler(void); +void USART3_IRQHandler(void); +void EXTI15_10_IRQHandler(void); +void RTCAlarm_IRQHandler(void); +void USBWakeUp_IRQHandler(void); +void TIM8_BRK_IRQHandler(void); +void TIM8_UP_IRQHandler(void); +void TIM8_TRG_COM_IRQHandler(void); +void TIM8_CC_IRQHandler(void); +void ADC3_IRQHandler(void); +void FSMC_IRQHandler(void); +void SDIO_IRQHandler(void); +void TIM5_IRQHandler(void); +void SPI3_IRQHandler(void); +void UART4_IRQHandler(void); +void UART5_IRQHandler(void); +void TIM6_IRQHandler(void); +void TIM7_IRQHandler(void); +void DMA2_Channel1_IRQHandler(void); +void DMA2_Channel2_IRQHandler(void); +void DMA2_Channel3_IRQHandler(void); +void DMA2_Channel4_5_IRQHandler(void); + +#endif /* __STM32F10x_IT_H */ + +/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/ diff --git a/bsp/stm32sky001/usart.c b/bsp/stm32sky001/usart.c new file mode 100644 index 0000000000000000000000000000000000000000..5a87dd4274eca720980799de93aa288eaf3f6f42 --- /dev/null +++ b/bsp/stm32sky001/usart.c @@ -0,0 +1,341 @@ +#include "usart.h" +#include + +#include +#include + +/* + * Use UART1 as console output and finsh input + * interrupt Rx and poll Tx (stream mode) + * + * Use UART2 with DMA Rx and poll Tx -- DMA channel 6 + * Use UART3 with DMA Tx and interrupt Rx -- DMA channel 2 + * + * USART DMA setting on STM32 + * USART1 Tx --> DMA Channel 4 + * USART1 Rx --> DMA Channel 5 + * USART2 Tx --> DMA Channel 7 + * USART2 Rx --> DMA Channel 6 + * USART3 Tx --> DMA Channel 2 + * USART3 Rx --> DMA Channel 3 + */ + +#ifdef RT_USING_UART1 +struct stm32_serial_int_rx uart1_int_rx; +struct stm32_serial_device uart1 = +{ + USART1, + &uart1_int_rx, + RT_NULL, + RT_NULL, + RT_NULL +}; +struct rt_device uart1_device; +#endif + +#ifdef RT_USING_UART2 +struct stm32_serial_int_rx uart2_int_rx; +struct stm32_serial_dma_rx uart2_dma_rx; +struct stm32_serial_device uart2 = +{ + USART2, + &uart2_int_rx, + &uart2_dma_rx, + RT_NULL, + RT_NULL +}; +struct rt_device uart2_device; +#endif + +#ifdef RT_USING_UART3 +struct stm32_serial_int_rx uart3_int_rx; +struct stm32_serial_dma_tx uart3_dma_tx; +struct stm32_serial_device uart3 = +{ + USART3, + &uart3_int_rx, + RT_NULL, + RT_NULL, + &uart3_dma_tx +}; +struct rt_device uart3_device; +#endif + +#define USART1_DR_Base 0x40013804 +#define USART2_DR_Base 0x40004404 +#define USART3_DR_Base 0x40004804 + +/* USART1_REMAP = 0 */ +#define UART1_GPIO_TX GPIO_Pin_9 +#define UART1_GPIO_RX GPIO_Pin_10 +#define UART1_GPIO GPIOA +#define RCC_APBPeriph_UART1 RCC_APB2Periph_USART1 +#define UART1_TX_DMA DMA1_Channel4 +#define UART1_RX_DMA DMA1_Channel5 + +/* USART2_REMAP = 0 */ +#define UART2_GPIO_TX GPIO_Pin_2 +#define UART2_GPIO_RX GPIO_Pin_3 +#define UART2_GPIO GPIOA +#define RCC_APBPeriph_UART2 RCC_APB1Periph_USART2 +#define UART2_TX_DMA DMA1_Channel7 +#define UART2_RX_DMA DMA1_Channel6 + +/* USART3_REMAP[1:0] = 00 */ +#define UART3_GPIO_RX GPIO_Pin_11 +#define UART3_GPIO_TX GPIO_Pin_10 +#define UART3_GPIO GPIOB +#define RCC_APBPeriph_UART3 RCC_APB1Periph_USART3 +#define UART3_TX_DMA DMA1_Channel2 +#define UART3_RX_DMA DMA1_Channel3 + +static void RCC_Configuration(void) +{ + RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE); + +#ifdef RT_USING_UART1 + /* Enable USART1 and GPIOA clocks */ + RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1 | RCC_APB2Periph_GPIOA, ENABLE); +#endif + +#ifdef RT_USING_UART2 + /* Enable GPIOD clocks */ + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOD, ENABLE); + /* Enable USART2 clock */ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE); +#endif + +#ifdef RT_USING_UART3 + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); + /* Enable USART3 clock */ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE); +#endif + +#if defined (RT_USING_UART2) || defined (RT_USING_UART3) + /* DMA clock enable */ + RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); +#endif +} + +static void GPIO_Configuration(void) +{ + GPIO_InitTypeDef GPIO_InitStructure; + +#ifdef RT_USING_UART1 + /* Configure USART1 Rx (PA.10) as input floating */ + GPIO_InitStructure.GPIO_Pin = UART1_GPIO_RX; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; + GPIO_Init(UART1_GPIO, &GPIO_InitStructure); + + /* Configure USART1 Tx (PA.09) as alternate function push-pull */ + GPIO_InitStructure.GPIO_Pin = UART1_GPIO_TX; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; + GPIO_Init(UART1_GPIO, &GPIO_InitStructure); +#endif + +#ifdef RT_USING_UART2 + /* Configure USART2 Rx as input floating */ + GPIO_InitStructure.GPIO_Pin = UART2_GPIO_RX; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; + GPIO_Init(UART2_GPIO, &GPIO_InitStructure); + + /* Configure USART2 Tx as alternate function push-pull */ + GPIO_InitStructure.GPIO_Pin = UART2_GPIO_TX; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_Init(UART2_GPIO, &GPIO_InitStructure); +#endif + +#ifdef RT_USING_UART3 + /* Configure USART3 Rx as input floating */ + GPIO_InitStructure.GPIO_Pin = UART3_GPIO_RX; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; + GPIO_Init(UART3_GPIO, &GPIO_InitStructure); + + /* Configure USART3 Tx as alternate function push-pull */ + GPIO_InitStructure.GPIO_Pin = UART3_GPIO_TX; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_Init(UART3_GPIO, &GPIO_InitStructure); +#endif +} + +static void NVIC_Configuration(void) +{ + NVIC_InitTypeDef NVIC_InitStructure; + + /* Configure the NVIC Preemption Priority Bits */ + NVIC_PriorityGroupConfig(NVIC_PriorityGroup_0); + +#ifdef RT_USING_UART1 + /* Enable the USART1 Interrupt */ + NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQChannel; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); +#endif + +#ifdef RT_USING_UART2 + /* Enable the USART2 Interrupt */ + NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQChannel; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); + + /* Enable the DMA1 Channel6 Interrupt */ + NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel6_IRQChannel; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); +#endif + +#ifdef RT_USING_UART3 + /* Enable the USART3 Interrupt */ + NVIC_InitStructure.NVIC_IRQChannel = USART3_IRQChannel; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); + + /* Enable the DMA1 Channel2 Interrupt */ + NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel2_IRQChannel; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); +#endif +} + +static void DMA_Configuration(void) +{ +#if defined(RT_USING_UART2) || defined (RT_USING_UART3) + DMA_InitTypeDef DMA_InitStructure; + + /* fill init structure */ + DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable; + DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; + DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte; + DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte; + DMA_InitStructure.DMA_Mode = DMA_Mode_Normal; + DMA_InitStructure.DMA_Priority = DMA_Priority_VeryHigh; + DMA_InitStructure.DMA_M2M = DMA_M2M_Disable; +#endif + +#ifdef RT_USING_UART2 + /* DMA1 Channel4 (triggered by USART2 Rx event) Config */ + DMA_DeInit(UART2_RX_DMA); + DMA_InitStructure.DMA_PeripheralBaseAddr = USART2_DR_Base; + DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC; + DMA_InitStructure.DMA_MemoryBaseAddr = (u32)0; + DMA_InitStructure.DMA_BufferSize = 0; + DMA_Init(UART2_RX_DMA, &DMA_InitStructure); + DMA_ITConfig(UART2_RX_DMA, DMA_IT_TC | DMA_IT_TE, ENABLE); + DMA_ClearFlag(DMA1_FLAG_TC4); +#endif + +#ifdef RT_USING_UART3 + /* DMA1 Channel5 (triggered by USART3 Tx event) Config */ + DMA_DeInit(UART3_TX_DMA); + DMA_InitStructure.DMA_PeripheralBaseAddr = USART3_DR_Base; + DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST; + DMA_InitStructure.DMA_MemoryBaseAddr = (u32)0; + DMA_InitStructure.DMA_BufferSize = 0; + DMA_Init(UART3_TX_DMA, &DMA_InitStructure); + DMA_ITConfig(UART3_TX_DMA, DMA_IT_TC | DMA_IT_TE, ENABLE); + DMA_ClearFlag(DMA1_FLAG_TC5); +#endif +} + +/* + * Init all related hardware in here + * rt_hw_serial_init() will register all supported USART device + */ +void rt_hw_usart_init() +{ + USART_InitTypeDef USART_InitStructure; + USART_ClockInitTypeDef USART_ClockInitStructure; + + RCC_Configuration(); + + GPIO_Configuration(); + + NVIC_Configuration(); + + DMA_Configuration(); + + /* uart init */ +#ifdef RT_USING_UART1 + USART_InitStructure.USART_BaudRate = 115200; + USART_InitStructure.USART_WordLength = USART_WordLength_8b; + USART_InitStructure.USART_StopBits = USART_StopBits_1; + USART_InitStructure.USART_Parity = USART_Parity_No; + USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None; + USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx; + USART_ClockInitStructure.USART_Clock = USART_Clock_Disable; + USART_ClockInitStructure.USART_CPOL = USART_CPOL_Low; + USART_ClockInitStructure.USART_CPHA = USART_CPHA_2Edge; + USART_ClockInitStructure.USART_LastBit = USART_LastBit_Disable; + USART_Init(USART1, &USART_InitStructure); + USART_ClockInit(USART1, &USART_ClockInitStructure); + + /* register uart1 */ + rt_hw_serial_register(&uart1_device, "uart1", + RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX | RT_DEVICE_FLAG_STREAM, + &uart1); + + /* enable interrupt */ + USART_ITConfig(USART1, USART_IT_RXNE, ENABLE); +#endif + +#ifdef RT_USING_UART2 + USART_InitStructure.USART_BaudRate = 115200; + USART_InitStructure.USART_WordLength = USART_WordLength_8b; + USART_InitStructure.USART_StopBits = USART_StopBits_1; + USART_InitStructure.USART_Parity = USART_Parity_No; + USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None; + USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx; + USART_ClockInitStructure.USART_Clock = USART_Clock_Disable; + USART_ClockInitStructure.USART_CPOL = USART_CPOL_Low; + USART_ClockInitStructure.USART_CPHA = USART_CPHA_2Edge; + USART_ClockInitStructure.USART_LastBit = USART_LastBit_Disable; + USART_Init(USART2, &USART_InitStructure); + USART_ClockInit(USART2, &USART_ClockInitStructure); + + uart2_dma_rx.dma_channel= UART2_RX_DMA; + + /* register uart2 */ + rt_hw_serial_register(&uart2_device, "uart2", + RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_DMA_RX, + &uart2); + + /* Enable USART2 DMA Rx request */ + USART_DMACmd(USART2, USART_DMAReq_Rx , ENABLE); +#endif + +#ifdef RT_USING_UART3 + USART_InitStructure.USART_BaudRate = 115200; + USART_InitStructure.USART_WordLength = USART_WordLength_8b; + USART_InitStructure.USART_StopBits = USART_StopBits_1; + USART_InitStructure.USART_Parity = USART_Parity_No; + USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None; + USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx; + USART_ClockInitStructure.USART_Clock = USART_Clock_Disable; + USART_ClockInitStructure.USART_CPOL = USART_CPOL_Low; + USART_ClockInitStructure.USART_CPHA = USART_CPHA_2Edge; + USART_ClockInitStructure.USART_LastBit = USART_LastBit_Disable; + USART_Init(USART3, &USART_InitStructure); + USART_ClockInit(USART3, &USART_ClockInitStructure); + + uart3_dma_tx.dma_channel= UART3_TX_DMA; + + /* register uart3 */ + rt_hw_serial_register(&uart3_device, "uart3", + RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX | RT_DEVICE_FLAG_DMA_TX, + &uart3); + + /* Enable USART3 DMA Tx request */ + USART_DMACmd(USART3, USART_DMAReq_Tx , ENABLE); + + /* enable interrupt */ + USART_ITConfig(USART3, USART_IT_RXNE, ENABLE); +#endif +} diff --git a/bsp/stm32sky001/usart.h b/bsp/stm32sky001/usart.h new file mode 100644 index 0000000000000000000000000000000000000000..ae74ffde7132a6288ae69ca580e2d7ece12d2fa7 --- /dev/null +++ b/bsp/stm32sky001/usart.h @@ -0,0 +1,9 @@ +#ifndef __USART_H__ +#define __USART_H__ + +#include +#include + +void rt_hw_usart_init(void); + +#endif