add eth driver

This commit is contained in:
tanek liang 2017-08-25 19:31:19 +08:00
parent ce4c351ebc
commit 09f698a209
13 changed files with 3615 additions and 142 deletions

View File

@ -12,15 +12,7 @@
*/
#include <rtthread.h>
#include <rtgui/rtgui.h>
#include <rtgui/rtgui_system.h>
#include <rtgui/rtgui_app.h>
#include <rtgui/widgets/window.h>
#include <rtgui/dc.h>
#include <rtgui/dc_hw.h>
#include "finsh.h"
#include <finsh.h>
#include "rtgui_demo.h"
#define DEBUG
@ -33,6 +25,14 @@
#ifdef RT_USING_GUIENGINE
#include <rtgui/rtgui.h>
#include <rtgui/rtgui_system.h>
#include <rtgui/rtgui_app.h>
#include <rtgui/widgets/window.h>
#include <rtgui/dc.h>
#include <rtgui/dc_hw.h>
struct rtgui_win *main_win;
rt_bool_t dc_event_handler(struct rtgui_object *object, rtgui_event_t *event);

View File

@ -11,6 +11,7 @@ drv_exmc_sdram.c
drv_usart.c
gd32f450z_lcd_eval.c
drv_lcd.c
drv_enet.c
""")
CPPPATH = [cwd]

View File

@ -0,0 +1,686 @@
/*
* File : eth_driver.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2012, 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
* 2011-11-30 aozima the first version.
* 2011-12-10 aozima support dual ethernet.
* 2011-12-21 aozima cleanup code.
* 2012-07-13 aozima mask all GMAC MMC Interrupt.
* 2012-07-20 aozima fixed mask all GMAC MMC Interrupt,and read clear.
* 2012-07-20 aozima use memcpy replace byte copy.
*/
#include <rtthread.h>
#include <rthw.h>
#include "lwipopts.h"
#include <netif/ethernetif.h>
#include <netif/etharp.h>
#include <lwip/icmp.h>
#include "gd32f4xx.h"
#include "synopsys_emac.h"
#define ETHERNET_MAC0 ((struct rt_synopsys_eth *)(0x40020000U + 0x00008000U))
//#define EMAC_DEBUG
//#define EMAC_RX_DUMP
//#define EMAC_TX_DUMP
#ifdef EMAC_DEBUG
#define EMAC_TRACE rt_kprintf
#else
#define EMAC_TRACE(...)
#endif
#define EMAC_RXBUFNB 4
#define EMAC_TXBUFNB 2
#define EMAC_PHY_AUTO 0
#define EMAC_PHY_10MBIT 1
#define EMAC_PHY_100MBIT 2
#define MAX_ADDR_LEN 6
struct gd32_emac
{
/* inherit from Ethernet device */
struct eth_device parent;
rt_uint8_t phy_mode;
/* interface address info. */
rt_uint8_t dev_addr[MAX_ADDR_LEN]; /* hw address */
struct rt_synopsys_eth * ETHERNET_MAC;
IRQn_Type ETHER_MAC_IRQ;
ALIGN(RT_ALIGN_SIZE)
PRAGMA(data_alignment=RT_ALIGN_SIZE)
EMAC_DMADESCTypeDef DMARxDscrTab[EMAC_RXBUFNB], DMATxDscrTab[EMAC_TXBUFNB];
ALIGN(RT_ALIGN_SIZE)
rt_uint8_t Rx_Buff[EMAC_RXBUFNB][EMAC_MAX_PACKET_SIZE];
ALIGN(RT_ALIGN_SIZE)
rt_uint8_t Tx_Buff[EMAC_TXBUFNB][EMAC_MAX_PACKET_SIZE];
EMAC_DMADESCTypeDef *DMATxDescToSet;
EMAC_DMADESCTypeDef *DMARxDescToGet;
struct rt_semaphore tx_buf_free;
};
static struct gd32_emac gd32_emac_device0;
/**
* Initializes the DMA Tx descriptors in chain mode.
*/
static void EMAC_DMA_tx_desc_init(EMAC_DMADESCTypeDef *DMATxDescTab, uint8_t* TxBuff, uint32_t TxBuffCount)
{
uint32_t i = 0;
EMAC_DMADESCTypeDef *DMATxDesc;
/* Fill each DMATxDesc descriptor with the right values */
for(i=0; i < TxBuffCount; i++)
{
/* Get the pointer on the ith member of the Tx Desc list */
DMATxDesc = DMATxDescTab + i;
/* Set Second Address Chained bit */
DMATxDesc->Status = EMAC_DMATxDesc_TCH;
/* Set Buffer1 address pointer */
DMATxDesc->Buffer1Addr = (uint32_t)(&TxBuff[i*EMAC_MAX_PACKET_SIZE]);
/* Initialize the next descriptor with the Next Descriptor Polling Enable */
if(i < (TxBuffCount-1))
{
/* Set next descriptor address register with next descriptor base address */
DMATxDesc->Buffer2NextDescAddr = (uint32_t)(DMATxDescTab+i+1);
}
else
{
/* For last descriptor, set next descriptor address register equal to the first descriptor base address */
DMATxDesc->Buffer2NextDescAddr = (uint32_t) DMATxDescTab;
}
}
}
/**
* Initializes the DMA Rx descriptors in chain mode.
*/
static void EMAC_DMA_rx_desc_init(EMAC_DMADESCTypeDef *DMARxDescTab, uint8_t *RxBuff, uint32_t RxBuffCount)
{
uint32_t i = 0;
EMAC_DMADESCTypeDef *DMARxDesc;
/* Fill each DMARxDesc descriptor with the right values */
for(i=0; i < RxBuffCount; i++)
{
/* Get the pointer on the ith member of the Rx Desc list */
DMARxDesc = DMARxDescTab+i;
/* Set Own bit of the Rx descriptor Status */
DMARxDesc->Status = EMAC_DMARxDesc_OWN;
/* Set Buffer1 size and Second Address Chained bit */
DMARxDesc->ControlBufferSize = EMAC_DMARxDesc_RCH | (uint32_t)EMAC_MAX_PACKET_SIZE;
/* Set Buffer1 address pointer */
DMARxDesc->Buffer1Addr = (uint32_t)(&RxBuff[i*EMAC_MAX_PACKET_SIZE]);
/* Initialize the next descriptor with the Next Descriptor Polling Enable */
if(i < (RxBuffCount-1))
{
/* Set next descriptor address register with next descriptor base address */
DMARxDesc->Buffer2NextDescAddr = (uint32_t)(DMARxDescTab+i+1);
}
else
{
/* For last descriptor, set next descriptor address register equal to the first descriptor base address */
DMARxDesc->Buffer2NextDescAddr = (uint32_t)(DMARxDescTab);
}
}
}
static rt_err_t gd32_emac_init(rt_device_t dev)
{
struct gd32_emac * gd32_emac_device;
struct rt_synopsys_eth * ETHERNET_MAC;
gd32_emac_device = (struct gd32_emac *)dev;
ETHERNET_MAC = gd32_emac_device->ETHERNET_MAC;
/* Software reset */
ETHERNET_MAC->BMR |= (1<<0); /* [bit0]SWR (Software Reset) */
/* Wait for software reset */
while(ETHERNET_MAC->BMR & (1<<0));
/* Configure ETHERNET */
EMAC_init(ETHERNET_MAC, SystemCoreClock);
/* mask all GMAC MMC Interrupt.*/
ETHERNET_MAC->mmc_cntl = (1<<3) | (1<<0); /* MMC Counter Freeze and reset. */
ETHERNET_MAC->mmc_intr_mask_rx = 0xFFFFFFFF;
ETHERNET_MAC->mmc_intr_mask_tx = 0xFFFFFFFF;
ETHERNET_MAC->mmc_ipc_intr_mask_rx = 0xFFFFFFFF;
/* Enable DMA Receive interrupt (need to enable in this case Normal interrupt) */
EMAC_INT_config(ETHERNET_MAC, EMAC_DMA_INT_NIS | EMAC_DMA_INT_R | EMAC_DMA_INT_T , ENABLE);
/* Initialize Tx Descriptors list: Chain Mode */
EMAC_DMA_tx_desc_init(gd32_emac_device->DMATxDscrTab, &gd32_emac_device->Tx_Buff[0][0], EMAC_TXBUFNB);
gd32_emac_device->DMATxDescToSet = gd32_emac_device->DMATxDscrTab;
/* Set Transmit Descriptor List Address Register */
ETHERNET_MAC->TDLAR = (uint32_t) gd32_emac_device->DMATxDescToSet;
/* Initialize Rx Descriptors list: Chain Mode */
EMAC_DMA_rx_desc_init(gd32_emac_device->DMARxDscrTab, &gd32_emac_device->Rx_Buff[0][0], EMAC_RXBUFNB);
gd32_emac_device->DMARxDescToGet = gd32_emac_device->DMARxDscrTab;
/* Set Receive Descriptor List Address Register */
ETHERNET_MAC->RDLAR = (uint32_t) gd32_emac_device->DMARxDescToGet;
/* MAC address configuration */
EMAC_MAC_Addr_config(ETHERNET_MAC, EMAC_MAC_Address0, (uint8_t*)&gd32_emac_device->dev_addr[0]);
NVIC_EnableIRQ( gd32_emac_device->ETHER_MAC_IRQ );
/* Enable MAC and DMA transmission and reception */
EMAC_start(ETHERNET_MAC);
return RT_EOK;
}
static rt_err_t gd32_emac_open(rt_device_t dev, rt_uint16_t oflag)
{
return RT_EOK;
}
static rt_err_t gd32_emac_close(rt_device_t dev)
{
return RT_EOK;
}
static rt_size_t gd32_emac_read(rt_device_t dev, rt_off_t pos, void* buffer, rt_size_t size)
{
rt_set_errno(-RT_ENOSYS);
return 0;
}
static rt_size_t gd32_emac_write (rt_device_t dev, rt_off_t pos, const void* buffer, rt_size_t size)
{
rt_set_errno(-RT_ENOSYS);
return 0;
}
static rt_err_t gd32_emac_control(rt_device_t dev, rt_uint8_t cmd, void *args)
{
struct gd32_emac * gd32_emac_device = (struct gd32_emac *)dev;
switch (cmd)
{
case NIOCTL_GADDR:
/* get mac address */
if (args) memcpy(args, &gd32_emac_device->dev_addr[0], MAX_ADDR_LEN);
else return -RT_ERROR;
break;
default :
break;
}
return RT_EOK;
}
static void EMAC_IRQHandler(struct gd32_emac * gd32_emac_device)
{
rt_uint32_t status, ier;
struct rt_synopsys_eth * ETHERNET_MAC;
ETHERNET_MAC = gd32_emac_device->ETHERNET_MAC;
/* get DMA IT status */
status = ETHERNET_MAC->SR;
ier = ETHERNET_MAC->IER;
/* GMAC MMC Interrupt. */
if(status & EMAC_DMA_INT_GMI)
{
volatile rt_uint32_t dummy;
volatile rt_uint32_t * reg;
EMAC_TRACE("EMAC_DMA_INT_GMI\r\n");
/* read clear all MMC interrupt. */
reg = &ETHERNET_MAC->mmc_cntl;
while((uint32_t)reg < (uint32_t)&ETHERNET_MAC->rxicmp_err_octets)
{
dummy = *reg++;
}
}
/* Normal interrupt summary. */
if(status & EMAC_DMA_INT_NIS)
{
rt_uint32_t nis_clear = EMAC_DMA_INT_NIS;
/* [0]:Transmit Interrupt. */
if((status & ier) & EMAC_DMA_INT_T) /* packet transmission */
{
rt_sem_release(&gd32_emac_device->tx_buf_free);
nis_clear |= EMAC_DMA_INT_T;
}
/* [2]:Transmit Buffer Unavailable. */
/* [6]:Receive Interrupt. */
if((status & ier) & EMAC_DMA_INT_R) /* packet reception */
{
/* a frame has been received */
eth_device_ready(&(gd32_emac_device->parent));
nis_clear |= EMAC_DMA_INT_R;
}
/* [14]:Early Receive Interrupt. */
EMAC_clear_pending(ETHERNET_MAC, nis_clear);
}
/* Abnormal interrupt summary. */
if( status & EMAC_DMA_INT_AIS)
{
rt_uint32_t ais_clear = EMAC_DMA_INT_AIS;
/* [1]:Transmit Process Stopped. */
/* [3]:Transmit Jabber Timeout. */
/* [4]: Receive FIFO Overflow. */
/* [5]: Transmit Underflow. */
/* [7]: Receive Buffer Unavailable. */
/* [8]: Receive Process Stopped. */
/* [9]: Receive Watchdog Timeout. */
/* [10]: Early Transmit Interrupt. */
/* [13]: Fatal Bus Error. */
EMAC_clear_pending(ETHERNET_MAC, ais_clear);
}
}
void ENET_IRQHandler(void)
{
/* enter interrupt */
rt_interrupt_enter();
EMAC_IRQHandler(&gd32_emac_device0);
/* leave interrupt */
rt_interrupt_leave();
}
/* EtherNet Device Interface */
rt_err_t gd32_emac_tx( rt_device_t dev, struct pbuf* p)
{
struct pbuf* q;
char * to;
struct gd32_emac * gd32_emac_device;
struct rt_synopsys_eth * ETHERNET_MAC;
gd32_emac_device = (struct gd32_emac *)dev;
ETHERNET_MAC = gd32_emac_device->ETHERNET_MAC;
/* get free tx buffer */
{
rt_err_t result;
result = rt_sem_take(&gd32_emac_device->tx_buf_free, RT_TICK_PER_SECOND/10);
if (result != RT_EOK) return -RT_ERROR;
}
to = (char *)gd32_emac_device->DMATxDescToSet->Buffer1Addr;
for (q = p; q != NULL; q = q->next)
{
/* Copy the frame to be sent into memory pointed by the current ETHERNET DMA Tx descriptor */
memcpy(to, q->payload, q->len);
to += q->len;
}
#ifdef EMAC_TX_DUMP
{
rt_uint32_t i;
rt_uint8_t *ptr = (rt_uint8_t*)(gd32_emac_device->DMATxDescToSet->Buffer1Addr);
EMAC_TRACE("\r\n%c%c tx_dump:", gd32_emac_device->parent.netif->name[0], gd32_emac_device->parent.netif->name[1]);
for(i=0; i<p->tot_len; i++)
{
if( (i%8) == 0 )
{
EMAC_TRACE(" ");
}
if( (i%16) == 0 )
{
EMAC_TRACE("\r\n");
}
EMAC_TRACE("%02x ",*ptr);
ptr++;
}
EMAC_TRACE("\r\ndump done!\r\n");
}
#endif
/* Setting the Frame Length: bits[12:0] */
gd32_emac_device->DMATxDescToSet->ControlBufferSize = (p->tot_len & EMAC_DMATxDesc_TBS1);
/* Setting the last segment and first segment bits (in this case a frame is transmitted in one descriptor) */
gd32_emac_device->DMATxDescToSet->Status |= EMAC_DMATxDesc_LS | EMAC_DMATxDesc_FS;
/* Enable TX Completion Interrupt */
gd32_emac_device->DMATxDescToSet->Status |= EMAC_DMATxDesc_IC;
#ifdef CHECKSUM_BY_HARDWARE
gd32_emac_device->DMATxDescToSet->Status |= EMAC_DMATxDesc_ChecksumTCPUDPICMPFull;
/* clean ICMP checksum */
{
struct eth_hdr *ethhdr = (struct eth_hdr *)(gd32_emac_device->DMATxDescToSet->Buffer1Addr);
/* is IP ? */
if( ethhdr->type == htons(ETHTYPE_IP) )
{
struct ip_hdr *iphdr = (struct ip_hdr *)(gd32_emac_device->DMATxDescToSet->Buffer1Addr + SIZEOF_ETH_HDR);
/* is ICMP ? */
if( IPH_PROTO(iphdr) == IP_PROTO_ICMP )
{
struct icmp_echo_hdr *iecho = (struct icmp_echo_hdr *)(gd32_emac_device->DMATxDescToSet->Buffer1Addr + SIZEOF_ETH_HDR + sizeof(struct ip_hdr) );
iecho->chksum = 0;
}
}
}
#endif
/* Set Own bit of the Tx descriptor Status: gives the buffer back to ETHERNET DMA */
gd32_emac_device->DMATxDescToSet->Status |= EMAC_DMATxDesc_OWN;
/* When Tx Buffer unavailable flag is set: clear it and resume transmission */
if ((ETHERNET_MAC->SR & EMAC_DMASR_TBUS) != (uint32_t)RESET)
{
/* Clear TBUS ETHERNET DMA flag */
ETHERNET_MAC->SR = EMAC_DMASR_TBUS;
/* Transmit Poll Demand to resume DMA transmission*/
ETHERNET_MAC->TPDR = 0;
}
/* Update the ETHERNET DMA global Tx descriptor with next Tx decriptor */
/* Chained Mode */
/* Selects the next DMA Tx descriptor list for next buffer to send */
gd32_emac_device->DMATxDescToSet = (EMAC_DMADESCTypeDef*) (gd32_emac_device->DMATxDescToSet->Buffer2NextDescAddr);
/* Return SUCCESS */
return RT_EOK;
}
/* reception a Ethernet packet. */
struct pbuf * gd32_emac_rx(rt_device_t dev)
{
struct pbuf* p;
rt_uint32_t framelength = 0;
struct gd32_emac * gd32_emac_device;
struct rt_synopsys_eth * ETHERNET_MAC;
gd32_emac_device = (struct gd32_emac *)dev;
ETHERNET_MAC = gd32_emac_device->ETHERNET_MAC;
/* init p pointer */
p = RT_NULL;
/* Check if the descriptor is owned by the ETHERNET DMA (when set) or CPU (when reset) */
if(((gd32_emac_device->DMARxDescToGet->Status & EMAC_DMARxDesc_OWN) != (uint32_t)RESET))
{
return p;
}
if (((gd32_emac_device->DMARxDescToGet->Status & EMAC_DMARxDesc_ES) == (uint32_t)RESET) &&
((gd32_emac_device->DMARxDescToGet->Status & EMAC_DMARxDesc_LS) != (uint32_t)RESET) &&
((gd32_emac_device->DMARxDescToGet->Status & EMAC_DMARxDesc_FS) != (uint32_t)RESET))
{
/* Get the Frame Length of the received packet: substruct 4 bytes of the CRC */
framelength = ((gd32_emac_device->DMARxDescToGet->Status & EMAC_DMARxDesc_FL)
>> EMAC_DMARXDESC_FRAME_LENGTHSHIFT) - 4;
/* allocate buffer */
p = pbuf_alloc(PBUF_LINK, framelength, PBUF_RAM);
if (p != RT_NULL)
{
const char * from;
struct pbuf* q;
from = (const char *)gd32_emac_device->DMARxDescToGet->Buffer1Addr;
for (q = p; q != RT_NULL; q= q->next)
{
/* Copy the received frame into buffer from memory pointed by the current ETHERNET DMA Rx descriptor */
memcpy(q->payload, from, q->len);
from += q->len;
}
#ifdef EMAC_RX_DUMP
{
rt_uint32_t i;
rt_uint8_t *ptr = (rt_uint8_t*)(gd32_emac_device->DMARxDescToGet->Buffer1Addr);
EMAC_TRACE("\r\n%c%c rx_dump:", gd32_emac_device->parent.netif->name[0], gd32_emac_device->parent.netif->name[1]);
for(i=0; i<p->tot_len; i++)
{
if( (i%8) == 0 )
{
EMAC_TRACE(" ");
}
if( (i%16) == 0 )
{
EMAC_TRACE("\r\n");
}
EMAC_TRACE("%02x ",*ptr);
ptr++;
}
EMAC_TRACE("\r\ndump done!\r\n");
}
#endif
}
}
/* Set Own bit of the Rx descriptor Status: gives the buffer back to ETHERNET DMA */
gd32_emac_device->DMARxDescToGet->Status = EMAC_DMARxDesc_OWN;
/* When Rx Buffer unavailable flag is set: clear it and resume reception */
if ((ETHERNET_MAC->SR & EMAC_DMASR_RBUS) != (uint32_t)RESET)
{
/* Clear RBUS ETHERNET DMA flag */
ETHERNET_MAC->SR = EMAC_DMASR_RBUS;
/* Resume DMA reception */
ETHERNET_MAC->RPDR = 0;
}
/* Update the ETHERNET DMA global Rx descriptor with next Rx decriptor */
/* Chained Mode */
if((gd32_emac_device->DMARxDescToGet->ControlBufferSize & EMAC_DMARxDesc_RCH) != (uint32_t)RESET)
{
/* Selects the next DMA Rx descriptor list for next buffer to read */
gd32_emac_device->DMARxDescToGet = (EMAC_DMADESCTypeDef*) (gd32_emac_device->DMARxDescToGet->Buffer2NextDescAddr);
}
else /* Ring Mode */
{
if((gd32_emac_device->DMARxDescToGet->ControlBufferSize & EMAC_DMARxDesc_RER) != (uint32_t)RESET)
{
/* Selects the first DMA Rx descriptor for next buffer to read: last Rx descriptor was used */
gd32_emac_device->DMARxDescToGet = (EMAC_DMADESCTypeDef*) (ETHERNET_MAC->RDLAR);
}
else
{
/* Selects the next DMA Rx descriptor list for next buffer to read */
gd32_emac_device->DMARxDescToGet = (EMAC_DMADESCTypeDef*) ((uint32_t)gd32_emac_device->DMARxDescToGet + 0x10 + ((ETHERNET_MAC->BMR & EMAC_DMABMR_DSL) >> 2));
}
}
return p;
}
/*
GPIO RMII0 RMII1 MII
PC0/E_RXER0_RXDV1 ch. 1 CRS_DV ch. 0 RX_ER
PC1/E_RX03_RX11 ch. 1 RXD [1] ch. 0 RXD [3]
PC2/E_RX02_RX10 ch. 1 RXD [0] ch. 0 RXD [2]
PC3/E_RX01 ch. 0 RXD [1] ch. 0 RXD [1]
PC4/E_RX00 ch. 0 RXD [0] ch. 0 RXD [0]
PC5/E_RXDV0 ch. 0 CRS_DV ch. 0 RX_DV
PC6/E_MDIO0 ch. 0 MDIO ch. 0 MDIO
PC7/E_MDC0 ch. 0 MDC ch. 0 MDC
PC8/E_RXCK0_REFCK ch. 0 REF_CLK ch. 1 REF_CLK ch. 0 RX_CLK
PC9/E_COL0 ch. 0 COL
PCA/E_CRS0 ch. 0 CRS
PCB/E_COUT REF_CLK output(??).
PCC/E_MDIO1 ch. 1 MDIO
PCD/E_TCK0_MDC1 ch. 1 MDC ch. 0 TX_CLK
PCE/E_TXER0_TXEN1 ch. 1 TX_EN ch. 0 TX_ER
PCF/E_TX03_TX11 ch. 1 TXD [1] ch. 0 TXD [3]
PD0/E_TX02_TX10 ch. 1 TXD [0] ch. 0 TXD [2]
PD1/E_TX01 ch. 0 TXD [1] ch. 0 TXD [1]
PD2/E_TX00 ch. 0 TXD [0] ch. 0 TXD [0]
PD3/E_TXEN0 ch. 0 TX_EN ch. 0 TX_EN
*/
/*!
\brief configures the nested vectored interrupt controller
\param[in] none
\param[out] none
\retval none
*/
static void nvic_configuration(void)
{
nvic_vector_table_set(NVIC_VECTTAB_FLASH, 0x0);
nvic_priority_group_set(NVIC_PRIGROUP_PRE2_SUB2);
nvic_irq_enable(ENET_IRQn, 0, 0);
}
/*!
\brief configures the different GPIO ports
\param[in] none
\param[out] none
\retval none
*/
static void enet_gpio_config(void)
{
rcu_periph_clock_enable(RCU_GPIOA);
rcu_periph_clock_enable(RCU_GPIOB);
rcu_periph_clock_enable(RCU_GPIOC);
rcu_periph_clock_enable(RCU_GPIOD);
rcu_periph_clock_enable(RCU_GPIOG);
rcu_periph_clock_enable(RCU_GPIOH);
rcu_periph_clock_enable(RCU_GPIOI);
gpio_af_set(GPIOA, GPIO_AF_0, GPIO_PIN_8);
gpio_mode_set(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_8);
gpio_output_options_set(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_200MHZ,GPIO_PIN_8);
/* enable SYSCFG clock */
rcu_periph_clock_enable(RCU_SYSCFG);
/* choose DIV2 to get 50MHz from 200MHz on CKOUT0 pin (PA8) to clock the PHY */
rcu_ckout0_config(RCU_CKOUT0SRC_PLLP, RCU_CKOUT0_DIV4);
syscfg_enet_phy_interface_config(SYSCFG_ENET_PHY_RMII);
/* PA1: ETH_RMII_REF_CLK */
gpio_mode_set(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_1);
gpio_output_options_set(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_200MHZ,GPIO_PIN_1);
/* PA2: ETH_MDIO */
gpio_mode_set(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_2);
gpio_output_options_set(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_200MHZ,GPIO_PIN_2);
/* PA7: ETH_RMII_CRS_DV */
gpio_mode_set(GPIOA, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_7);
gpio_output_options_set(GPIOA, GPIO_OTYPE_PP, GPIO_OSPEED_200MHZ,GPIO_PIN_7);
gpio_af_set(GPIOA, GPIO_AF_11, GPIO_PIN_1);
gpio_af_set(GPIOA, GPIO_AF_11, GPIO_PIN_2);
gpio_af_set(GPIOA, GPIO_AF_11, GPIO_PIN_7);
/* PB11: ETH_RMII_TX_EN */
gpio_mode_set(GPIOB, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_11);
gpio_output_options_set(GPIOB, GPIO_OTYPE_PP, GPIO_OSPEED_200MHZ,GPIO_PIN_11);
/* PB12: ETH_RMII_TXD0 */
gpio_mode_set(GPIOB, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_12);
gpio_output_options_set(GPIOB, GPIO_OTYPE_PP, GPIO_OSPEED_200MHZ,GPIO_PIN_12);
/* PB13: ETH_RMII_TXD1 */
gpio_mode_set(GPIOB, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_13);
gpio_output_options_set(GPIOB, GPIO_OTYPE_PP, GPIO_OSPEED_200MHZ,GPIO_PIN_13);
gpio_af_set(GPIOB, GPIO_AF_11, GPIO_PIN_11);
gpio_af_set(GPIOB, GPIO_AF_11, GPIO_PIN_12);
gpio_af_set(GPIOB, GPIO_AF_11, GPIO_PIN_13);
/* PC1: ETH_MDC */
gpio_mode_set(GPIOC, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_1);
gpio_output_options_set(GPIOC, GPIO_OTYPE_PP, GPIO_OSPEED_200MHZ,GPIO_PIN_1);
/* PC4: ETH_RMII_RXD0 */
gpio_mode_set(GPIOC, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_4);
gpio_output_options_set(GPIOC, GPIO_OTYPE_PP, GPIO_OSPEED_200MHZ,GPIO_PIN_4);
/* PC5: ETH_RMII_RXD1 */
gpio_mode_set(GPIOC, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO_PIN_5);
gpio_output_options_set(GPIOC, GPIO_OTYPE_PP, GPIO_OSPEED_200MHZ,GPIO_PIN_5);
gpio_af_set(GPIOC, GPIO_AF_11, GPIO_PIN_1);
gpio_af_set(GPIOC, GPIO_AF_11, GPIO_PIN_4);
gpio_af_set(GPIOC, GPIO_AF_11, GPIO_PIN_5);
}
int rt_hw_gd32_eth_init(void)
{
rt_kprintf("rt_gd32_eth_init...\n");
/* enable ethernet clock */
rcu_periph_clock_enable(RCU_ENET);
rcu_periph_clock_enable(RCU_ENETTX);
rcu_periph_clock_enable(RCU_ENETRX);
nvic_configuration();
/* configure the GPIO ports for ethernet pins */
enet_gpio_config();
/* set autonegotiation mode */
gd32_emac_device0.phy_mode = EMAC_PHY_AUTO;
gd32_emac_device0.ETHERNET_MAC = ETHERNET_MAC0;
gd32_emac_device0.ETHER_MAC_IRQ = ENET_IRQn;
// OUI 00-00-0E FUJITSU LIMITED
gd32_emac_device0.dev_addr[0] = 0x00;
gd32_emac_device0.dev_addr[1] = 0x00;
gd32_emac_device0.dev_addr[2] = 0x0E;
/* set mac address: (only for test) */
gd32_emac_device0.dev_addr[3] = 0x12;
gd32_emac_device0.dev_addr[4] = 0x34;
gd32_emac_device0.dev_addr[5] = 0x56;
gd32_emac_device0.parent.parent.init = gd32_emac_init;
gd32_emac_device0.parent.parent.open = gd32_emac_open;
gd32_emac_device0.parent.parent.close = gd32_emac_close;
gd32_emac_device0.parent.parent.read = gd32_emac_read;
gd32_emac_device0.parent.parent.write = gd32_emac_write;
gd32_emac_device0.parent.parent.control = gd32_emac_control;
gd32_emac_device0.parent.parent.user_data = RT_NULL;
gd32_emac_device0.parent.eth_rx = gd32_emac_rx;
gd32_emac_device0.parent.eth_tx = gd32_emac_tx;
/* init tx buffer free semaphore */
rt_sem_init(&gd32_emac_device0.tx_buf_free, "tx_buf0", EMAC_TXBUFNB, RT_IPC_FLAG_FIFO);
eth_device_init(&(gd32_emac_device0.parent), "e0");
return 0;
}
INIT_DEVICE_EXPORT(rt_hw_gd32_eth_init);

View File

@ -9,7 +9,7 @@
*
* Change Logs:
* Date Author Notes
* 2009-01-05 Tanek the first version
* 2017-08-23 Tanek the first version
*/
#include "gd32f450z_lcd_eval.h"

File diff suppressed because it is too large Load Diff

View File

@ -20,7 +20,7 @@
#include "gd32f4xx_dbg.h"
#include "gd32f4xx_dci.h"
#include "gd32f4xx_dma.h"
#include "gd32f4xx_enet.h"
//#include "gd32f4xx_enet.h"
#include "gd32f4xx_exmc.h"
#include "gd32f4xx_exti.h"
#include "gd32f4xx_fmc.h"

View File

@ -0,0 +1,401 @@
/*
* File : rthw.h
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2012, RT-Thread Development Team
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*/
#include "synopsys_emac.h"
/* Global pointers on Tx and Rx descriptor used to track transmit and receive descriptors */
extern EMAC_DMADESCTypeDef *DMATxDescToSet;
extern EMAC_DMADESCTypeDef *DMARxDescToGet;
/**
* Initializes the ETHERNET peripheral according to the specified
*/
rt_uint32_t EMAC_init(struct rt_synopsys_eth * ETHERNET_MAC, rt_uint32_t SystemCoreClock)
{
rt_uint32_t value = 0;
/*-------------------------------- MAC Config ------------------------------*/
/*---------------------- ETHERNET MACMIIAR Configuration -------------------*/
/* Get the ETHERNET MACMIIAR value */
value = ETHERNET_MAC->GAR;
/* Clear CSR Clock Range CR[2:0] bits */
value &= MACMIIAR_CR_MASK;
/* Get hclk frequency value */
/* Set CR bits depending on hclk value */
if((SystemCoreClock >= 20000000)&&(SystemCoreClock < 35000000))
{
/* CSR Clock Range between 20-35 MHz */
value |= (rt_uint32_t)EMAC_MACMIIAR_CR_Div16;
}
else if((SystemCoreClock >= 35000000)&&(SystemCoreClock < 60000000))
{
/* CSR Clock Range between 35-60 MHz */
value |= (rt_uint32_t)EMAC_MACMIIAR_CR_Div26;
}
else if((SystemCoreClock >= 60000000)&&(SystemCoreClock <= 100000000))
{
/* CSR Clock Range between 60-100 MHz */
value |= (rt_uint32_t)EMAC_MACMIIAR_CR_Div42;
}
else if((SystemCoreClock >= 100000000)&&(SystemCoreClock <= 150000000))
{
/* CSR Clock Range between 100-150 MHz */
value |= (rt_uint32_t)EMAC_MACMIIAR_CR_Div62;
}
else if((SystemCoreClock >= 150000000)&&(SystemCoreClock <= 250000000))
{
/* CSR Clock Range between 150-250 MHz */
value |= (rt_uint32_t)EMAC_MACMIIAR_CR_Div102;
}
else /* if((SystemCoreClock >= 250000000)&&(SystemCoreClock <= 300000000)) */
{
/* CSR Clock Range between 250-300 MHz */
value |= (rt_uint32_t)EMAC_MACMIIAR_CR_Div122;
}
/* Write to ETHERNET MAC MIIAR: Configure the ETHERNET CSR Clock Range */
ETHERNET_MAC->GAR = (rt_uint32_t)value;
/*------------------------ ETHERNET MACCR Configuration --------------------*/
/* Get the ETHERNET MACCR value */
value = ETHERNET_MAC->MCR;
/* Clear WD, PCE, PS, TE and RE bits */
value &= MACCR_CLEAR_MASK;
value |= (rt_uint32_t)(EMAC_Watchdog_Enable |
EMAC_Jabber_Enable |
EMAC_InterFrameGap_96Bit |
EMAC_CarrierSense_Enable |
EMAC_Speed_100M |
EMAC_ReceiveOwn_Enable |
EMAC_LoopbackMode_Disable |
EMAC_Mode_FullDuplex |
EMAC_ChecksumOffload_Enable |
EMAC_RetryTransmission_Disable |
EMAC_AutomaticPadCRCStrip_Disable |
EMAC_BackOffLimit_10 |
EMAC_DeferralCheck_Disable);
/* Write to ETHERNET MACCR */
value |= (1<<15);
value &= ~(1<<25);
value &= ~(1<<24);
ETHERNET_MAC->MCR = (rt_uint32_t)value;
/*----------------------- ETHERNET MACFFR Configuration --------------------*/
/* Write to ETHERNET MACFFR */
ETHERNET_MAC->MFFR = (rt_uint32_t)(EMAC_ReceiveAll_Enable |
EMAC_SourceAddrFilter_Disable |
EMAC_PassControlFrames_BlockAll |
EMAC_BroadcastFramesReception_Disable |
EMAC_DestinationAddrFilter_Normal |
EMAC_PromiscuousMode_Disable |
EMAC_MulticastFramesFilter_Perfect |
EMAC_UnicastFramesFilter_Perfect);
/*--------------- ETHERNET MACHTHR and MACHTLR Configuration ---------------*/
/* Write to ETHERNET MACHTHR */
ETHERNET_MAC->MHTRH = 0;
/* Write to ETHERNET MACHTLR */
ETHERNET_MAC->MHTRL = 0;
/*----------------------- ETHERNET MACFCR Configuration --------------------*/
/* Get the ETHERNET MACFCR value */
value = ETHERNET_MAC->FCR;
/* Clear xx bits */
value &= MACFCR_CLEAR_MASK;
value |= (rt_uint32_t)((0 << 16) |
EMAC_ZeroQuantaPause_Disable |
EMAC_PauseLowThreshold_Minus4 |
EMAC_UnicastPauseFrameDetect_Disable |
EMAC_ReceiveFlowControl_Disable |
EMAC_TransmitFlowControl_Disable);
/* Write to ETHERNET MACFCR */
ETHERNET_MAC->FCR = (rt_uint32_t)value;
/*----------------------- ETHERNET MACVLANTR Configuration -----------------*/
ETHERNET_MAC->VTR = (rt_uint32_t)(EMAC_VLANTagComparison_16Bit |
0);
/*-------------------------------- DMA Config ------------------------------*/
/*----------------------- ETHERNET DMAOMR Configuration --------------------*/
/* Get the ETHERNET DMAOMR value */
value = ETHERNET_MAC->OMR;
/* Clear xx bits */
value &= DMAOMR_CLEAR_MASK;
value |= (rt_uint32_t)(EMAC_DropTCPIPChecksumErrorFrame_Disable |
EMAC_ReceiveStoreForward_Enable |
EMAC_FlushReceivedFrame_Enable |
EMAC_TransmitStoreForward_Enable |
EMAC_TransmitThresholdControl_64Bytes |
EMAC_ForwardErrorFrames_Disable |
EMAC_ForwardUndersizedGoodFrames_Disable |
EMAC_ReceiveThresholdControl_64Bytes |
EMAC_SecondFrameOperate_Disable);
/* Write to ETHERNET DMAOMR */
ETHERNET_MAC->OMR = (rt_uint32_t)value;
/*----------------------- ETHERNET DMABMR Configuration --------------------*/
ETHERNET_MAC->BMR = (rt_uint32_t)(EMAC_AddressAlignedBeats_Enable |
EMAC_FixedBurst_Enable |
EMAC_RxDMABurstLength_32Beat | /* !! if 4xPBL is selected for Tx or Rx it is applied for the other */
EMAC_TxDMABurstLength_32Beat |
(0 << 2) |
EMAC_DMAArbitration_RoundRobin_RxTx_2_1 |
EMAC_DMABMR_USP); /* Enable use of separate PBL for Rx and Tx */
/* Return Ethernet configuration success */
return EMAC_SUCCESS;
}
/**
* Enables or disables the specified ETHERNET DMA interrupts.
*/
void EMAC_INT_config(struct rt_synopsys_eth * ETHERNET_MAC, rt_uint32_t EMAC_DMA_IT, rt_bool_t NewState)
{
if (NewState)
{
/* Enable the selected ETHERNET DMA interrupts */
ETHERNET_MAC->IER |= EMAC_DMA_IT;
}
else
{
/* Disable the selected ETHERNET DMA interrupts */
ETHERNET_MAC->IER &=(~(rt_uint32_t)EMAC_DMA_IT);
}
}
/**
* Configures the selected MAC address.
*/
void EMAC_MAC_Addr_config(struct rt_synopsys_eth * ETHERNET_MAC, rt_uint32_t MacAddr, rt_uint8_t *Addr)
{
rt_uint32_t value;
/* Calculate the selectecd MAC address high register */
value = ((rt_uint32_t)Addr[5] << 8) | (rt_uint32_t)Addr[4];
/* Load the selectecd MAC address high register */
//(*(volatile rt_uint32_t *) (EMAC_MAC_ADDR_HBASE + MacAddr)) = value;
ETHERNET_MAC->MARs[MacAddr].MARH = value;
/* Calculate the selectecd MAC address low register */
value = ((rt_uint32_t)Addr[3] << 24) | ((rt_uint32_t)Addr[2] << 16) | ((rt_uint32_t)Addr[1] << 8) | Addr[0];
/* Load the selectecd MAC address low register */
//(*(volatile rt_uint32_t *) (EMAC_MAC_ADDR_LBASE + MacAddr)) = value;
ETHERNET_MAC->MARs[MacAddr].MARL = value;
}
/**
* Enables or disables the MAC transmission.
*/
void EMAC_MACTransmissionCmd(struct rt_synopsys_eth * ETHERNET_MAC, rt_bool_t NewState)
{
if (NewState)
{
/* Enable the MAC transmission */
ETHERNET_MAC->MCR |= EMAC_MACCR_TE;
}
else
{
/* Disable the MAC transmission */
ETHERNET_MAC->MCR &= ~EMAC_MACCR_TE;
}
}
/**
* Clears the ETHERNET transmit FIFO.
*/
void EMAC_FlushTransmitFIFO(struct rt_synopsys_eth * ETHERNET_MAC)
{
/* Set the Flush Transmit FIFO bit */
ETHERNET_MAC->OMR |= EMAC_DMAOMR_FTF;
}
/**
* Enables or disables the MAC reception.
*/
void EMAC_MACReceptionCmd(struct rt_synopsys_eth * ETHERNET_MAC, rt_bool_t NewState)
{
if (NewState)
{
/* Enable the MAC reception */
ETHERNET_MAC->MCR |= EMAC_MACCR_RE;
}
else
{
/* Disable the MAC reception */
ETHERNET_MAC->MCR &= ~EMAC_MACCR_RE;
}
}
/**
* Enables or disables the DMA transmission.
*/
void EMAC_DMATransmissionCmd(struct rt_synopsys_eth * ETHERNET_MAC, rt_bool_t NewState)
{
if (NewState)
{
/* Enable the DMA transmission */
ETHERNET_MAC->OMR |= EMAC_DMAOMR_ST;
}
else
{
/* Disable the DMA transmission */
ETHERNET_MAC->OMR &= ~EMAC_DMAOMR_ST;
}
}
/**
* Enables or disables the DMA reception.
*/
void EMAC_DMAReceptionCmd(struct rt_synopsys_eth * ETHERNET_MAC, rt_bool_t NewState)
{
if (NewState)
{
/* Enable the DMA reception */
ETHERNET_MAC->OMR |= EMAC_DMAOMR_SR;
}
else
{
/* Disable the DMA reception */
ETHERNET_MAC->OMR &= ~EMAC_DMAOMR_SR;
}
}
/**
* Enables ENET MAC and DMA reception/transmission
*/
void EMAC_start(struct rt_synopsys_eth * ETHERNET_MAC)
{
/* Enable transmit state machine of the MAC for transmission on the MII */
EMAC_MACTransmissionCmd(ETHERNET_MAC, RT_TRUE);
/* Flush Transmit FIFO */
EMAC_FlushTransmitFIFO(ETHERNET_MAC);
/* Enable receive state machine of the MAC for reception from the MII */
EMAC_MACReceptionCmd(ETHERNET_MAC, RT_TRUE);
/* Start DMA transmission */
EMAC_DMATransmissionCmd(ETHERNET_MAC, RT_TRUE);
/* Start DMA reception */
EMAC_DMAReceptionCmd(ETHERNET_MAC, RT_TRUE);
}
/**
* Clears the ETHERNET's DMA interrupt pending bit.
*/
void EMAC_clear_pending(struct rt_synopsys_eth * ETHERNET_MAC, rt_uint32_t pending)
{
/* Clear the selected ETHERNET DMA IT */
ETHERNET_MAC->SR = (rt_uint32_t) pending;
}
/**
* Resumes the DMA Transmission by writing to the DmaRxPollDemand register
* (the data written could be anything). This forces the DMA to resume reception.
*/
void EMAC_resume_reception(struct rt_synopsys_eth * ETHERNET_MAC)
{
ETHERNET_MAC->RPDR = 0;
}
/**
* Resumes the DMA Transmission by writing to the DmaTxPollDemand register
* (the data written could be anything). This forces the DMA to resume transmission.
*/
void EMAC_resume_transmission(struct rt_synopsys_eth * ETHERNET_MAC)
{
ETHERNET_MAC->TPDR = 0;
}
/**
* Read a PHY register
*/
rt_uint16_t EMAC_PHY_read(struct rt_synopsys_eth * ETHERNET_MAC, rt_uint16_t PHYAddress, rt_uint16_t PHYReg)
{
rt_uint32_t value = 0;
volatile rt_uint32_t timeout = 0;
/* Get the ETHERNET MACMIIAR value */
value = ETHERNET_MAC->GAR;
/* Keep only the CSR Clock Range CR[2:0] bits value */
value &= ~MACMIIAR_CR_MASK;
/* Prepare the MII address register value */
value |=(((rt_uint32_t)PHYAddress<<11) & EMAC_MACMIIAR_PA); /* Set the PHY device address */
value |=(((rt_uint32_t)PHYReg<<6) & EMAC_MACMIIAR_MR); /* Set the PHY register address */
value &= ~EMAC_MACMIIAR_MW; /* Set the read mode */
value |= EMAC_MACMIIAR_MB; /* Set the MII Busy bit */
/* Write the result value into the MII Address register */
ETHERNET_MAC->GAR = value;
/* Check for the Busy flag */
do
{
timeout++;
value = ETHERNET_MAC->GAR;
}
while ((value & EMAC_MACMIIAR_MB) && (timeout < (rt_uint32_t)PHY_READ_TO));
/* Return ERROR in case of timeout */
if(timeout == PHY_READ_TO)
{
return (rt_uint16_t)EMAC_ERROR;
}
/* Return data register value */
return (rt_uint16_t)(ETHERNET_MAC->GDR);
}
/**
* Write to a PHY register
*/
rt_uint32_t EMAC_PHY_write(struct rt_synopsys_eth * ETHERNET_MAC, rt_uint16_t PHYAddress, rt_uint16_t PHYReg, rt_uint16_t PHYValue)
{
rt_uint32_t value = 0;
volatile rt_uint32_t timeout = 0;
/* Get the ETHERNET MACMIIAR value */
value = ETHERNET_MAC->GAR;
/* Keep only the CSR Clock Range CR[2:0] bits value */
value &= ~MACMIIAR_CR_MASK;
/* Prepare the MII register address value */
value |=(((rt_uint32_t)PHYAddress<<11) & EMAC_MACMIIAR_PA); /* Set the PHY device address */
value |=(((rt_uint32_t)PHYReg<<6) & EMAC_MACMIIAR_MR); /* Set the PHY register address */
value |= EMAC_MACMIIAR_MW; /* Set the write mode */
value |= EMAC_MACMIIAR_MB; /* Set the MII Busy bit */
/* Give the value to the MII data register */
ETHERNET_MAC->GDR = PHYValue;
/* Write the result value into the MII Address register */
ETHERNET_MAC->GAR = value;
/* Check for the Busy flag */
do
{
timeout++;
value = ETHERNET_MAC->GAR;
}
while ((value & EMAC_MACMIIAR_MB) && (timeout < (rt_uint32_t)PHY_WRITE_TO));
/* Return ERROR in case of timeout */
if(timeout == PHY_WRITE_TO)
{
return EMAC_ERROR;
}
/* Return SUCCESS */
return EMAC_SUCCESS;
}

File diff suppressed because it is too large Load Diff

View File

@ -339,10 +339,14 @@
</option>
<option>
<name>CCIncludePath2</name>
<state>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src</state>
<state>$PROJ_DIR$\..\..\..\git\rt-thread\libcpu\arm\cortex-m4</state>
<state>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\include</state>
<state>$PROJ_DIR$\..\..\..\git\rt-thread\include</state>
<state>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\arch\include</state>
<state>$PROJ_DIR$\drivers</state>
<state>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\include</state>
<state>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\include\ipv4</state>
<state>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\include\netif</state>
<state>$PROJ_DIR$\Libraries\GD32F4xx_standard_peripheral\Include</state>
<state>$PROJ_DIR$\.</state>
<state>$PROJ_DIR$\applications</state>
@ -1367,10 +1371,14 @@
</option>
<option>
<name>CCIncludePath2</name>
<state>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src</state>
<state>$PROJ_DIR$\..\..\..\git\rt-thread\libcpu\arm\cortex-m4</state>
<state>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\include</state>
<state>$PROJ_DIR$\..\..\..\git\rt-thread\include</state>
<state>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\arch\include</state>
<state>$PROJ_DIR$\drivers</state>
<state>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\include</state>
<state>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\include\ipv4</state>
<state>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\include\netif</state>
<state>$PROJ_DIR$\Libraries\GD32F4xx_standard_peripheral\Include</state>
<state>$PROJ_DIR$\.</state>
<state>$PROJ_DIR$\applications</state>
@ -2072,6 +2080,9 @@
<file>
<name>$PROJ_DIR$\applications\mem_test.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\components\net\lwip-2.0.2\src\apps\ping\ping.c</name>
</file>
<file>
<name>$PROJ_DIR$\applications\rtgui_demo.c</name>
</file>
@ -2141,6 +2152,9 @@
<file>
<name>$PROJ_DIR$\drivers\board.c</name>
</file>
<file>
<name>$PROJ_DIR$\drivers\drv_enet.c</name>
</file>
<file>
<name>$PROJ_DIR$\drivers\drv_exmc_sdram.c</name>
</file>
@ -2153,6 +2167,9 @@
<file>
<name>$PROJ_DIR$\drivers\gd32f450z_lcd_eval.c</name>
</file>
<file>
<name>$PROJ_DIR$\drivers\synopsys_emac.c</name>
</file>
</group>
<group>
<name>finsh</name>
@ -2292,129 +2309,6 @@
<name>$PROJ_DIR$\Libraries\CMSIS\GD\GD32F4xx\Source\system_gd32f4xx.c</name>
</file>
</group>
<group>
<name>GUIEngine</name>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\asc12font.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\asc16font.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\blit.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\box.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\color.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\container.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\dc.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\dc_blend.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\dc_buffer.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\dc_client.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\dc_hw.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\dc_rotozoom.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\dc_trans.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\filerw.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\font.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\font_bmp.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\font_fnt.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\font_freetype.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\font_hz_bmp.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\font_hz_file.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\hz12font.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\hz16font.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\image.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\image_bmp.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\image_hdc.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\image_jpg.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\image_png.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\image_xpm.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\matrix.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\mouse.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\region.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\rtgui_app.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\rtgui_driver.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\rtgui_object.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\rtgui_system.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\server.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\title.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\topwin.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\widget.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\gui\src\window.c</name>
</file>
</group>
<group>
<name>Kernel</name>
<file>
@ -2463,4 +2357,112 @@
<name>$PROJ_DIR$\..\..\..\git\rt-thread\src\timer.c</name>
</file>
</group>
<group>
<name>LwIP</name>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\api\api_lib.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\api\api_msg.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\ipv4\autoip.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\def.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\dhcp.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\dns.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\api\err.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\netif\etharp.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\netif\ethernetif.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\ipv4\icmp.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\ipv4\igmp.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\ipv4\inet.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\ipv4\inet_chksum.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\init.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\ipv4\ip.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\ipv4\ip_addr.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\ipv4\ip_frag.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\memp.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\api\netbuf.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\api\netdb.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\netif.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\api\netifapi.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\pbuf.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\raw.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\netif\slipif.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\api\sockets.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\stats.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\sys.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\arch\sys_arch.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\tcp.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\tcp_in.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\tcp_out.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\api\tcpip.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\timers.c</name>
</file>
<file>
<name>$PROJ_DIR$\..\..\..\git\rt-thread\components\net\lwip-1.4.1\src\core\udp.c</name>
</file>
</group>
</project>

View File

@ -10,6 +10,7 @@
<TargetName>rt-thread_gd32f4xx</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<pCCUsed>5060422::V5.06 update 4 (build 422)::ARMCC</pCCUsed>
<TargetOption>
<TargetCommonOption>
<Device>GD32F450ZK</Device>
@ -403,6 +404,11 @@
<FileType>1</FileType>
<FilePath>applications\startup.c</FilePath>
</File>
<File>
<FileName>rtgui_demo.c</FileName>
<FileType>1</FileType>
<FilePath>.\applications\rtgui_demo.c</FilePath>
</File>
</Files>
</Group>
<Group>

View File

@ -66,7 +66,7 @@
/* SECTION: RTGUI support */
/* using RTGUI support */
#define RT_USING_GUIENGINE
//#define RT_USING_GUIENGINE
/* name length of RTGUI object */
#define RTGUI_NAME_MAX 16
@ -159,7 +159,7 @@
// #define RT_USING_DFS_ROMFS
/* SECTION: lwip, a lighwight TCP/IP protocol stack */
//#define RT_USING_LWIP
#define RT_USING_LWIP
/* LwIP uses RT-Thread Memory Management */
#define RT_LWIP_USING_RT_MEM
/* Enable ICMP protocol*/
@ -173,7 +173,7 @@
/* Enable DHCP */
#define RT_LWIP_DHCP
/* Enable DEBUG */
//#define RT_LWIP_DEBUG
#define RT_LWIP_DEBUG
/* the number of simulatenously active TCP connections*/
#define RT_LWIP_TCP_PCB_NUM 5
@ -181,13 +181,13 @@
/* ip address of target*/
#define RT_LWIP_IPADDR0 192
#define RT_LWIP_IPADDR1 168
#define RT_LWIP_IPADDR2 1
#define RT_LWIP_IPADDR3 201
#define RT_LWIP_IPADDR2 10
#define RT_LWIP_IPADDR3 222
/* gateway address of target*/
#define RT_LWIP_GWADDR0 192
#define RT_LWIP_GWADDR1 168
#define RT_LWIP_GWADDR2 1
#define RT_LWIP_GWADDR2 10
#define RT_LWIP_GWADDR3 1
/* mask address of target*/

View File

@ -10,6 +10,8 @@
<TargetName>rtthread-stm32</TargetName>
<ToolsetNumber>0x4</ToolsetNumber>
<ToolsetName>ARM-ADS</ToolsetName>
<pArmCC>5050169::V5.05 update 2 (build 169)::.\ARMCC_505u2</pArmCC>
<pCCUsed>5050169::V5.05 update 2 (build 169)::.\ARMCC_505u2</pCCUsed>
<TargetOption>
<TargetCommonOption>
<Device>STM32F103ZE</Device>

View File

@ -194,4 +194,6 @@
/* nanopb support */
/* #define RT_USING_NANOPB */
#define RT_USING_CPU_FFS
#endif