打印
[活动专区]

AT-START-F437测评】CycloneTCP网络协议栈移植

[复制链接]
1243|15
手机看帖
扫描二维码
随时随地手机跟帖
跳转到指定楼层
楼主
乱世流年|  楼主 | 2023-1-3 09:43 | 只看该作者 回帖奖励 |倒序浏览 |阅读模式
年前申请了AT32F437-START开发板,冲着板载的网络和超大的flash和内存空间,然后根据项目实际使用的协议栈,将CycloneTCP协议栈移植到此开发板上,目前已经实现可以发出IGMPV2协议报文,但是网络指示灯一直显示自协商的网络速度为10MHz,电脑端可以识别网卡设备,且使用ping指令无法正常ping通,现将相应的代码发上来,希望能得到官方的协助,帮忙讲解下EMAC外设的相关初始化流程和中断DMA收发数据的正确操作模式。


at32f437_eth_driver.c源码

/**
* @file at32f437_eth_driver.c
* @brief AT32F437 Ethernet MAC driver
*
* @section License
*
* Copyright (C) 2010-2022 Oryx Embedded SARL. All rights reserved.
*
* This file is part of CycloneTCP Eval.
*
* This software is provided in source form for a short-term evaluation only. The
* evaluation license expires 90 days after the date you first download the software.
*
* If you plan to use this software in a commercial product, you are required to
* purchase a commercial license from Oryx Embedded SARL.
*
* After the 90-day evaluation period, you agree to either purchase a commercial
* license or delete all copies of this software. If you wish to extend the
* evaluation period, you must contact sales@oryx-embedded.com.
*
* This evaluation software is provided "as is" without warranty of any kind.
* Technical support is available as an option during the evaluation period.
*
* @author Oryx Embedded SARL (www.oryx-embedded.com)
* @version 2.1.8
**/

//Switch to the appropriate trace level
#define TRACE_LEVEL NIC_TRACE_LEVEL

//Dependencies
#include "at32f435_437.h"
#include "core/net.h"
#include "drivers/mac/at32f437_eth_driver.h"
#include "debug.h"


#define PHY_ADDRESS                      (0x03)       /*!< relative to at32 board */
#define PHY_CONTROL_REG                  (0x00)       /*!< basic mode control register */
#define PHY_RESET_BIT                    (0x8000)     /*!< reset phy */
#define CHECKSUM_BY_HARDWARE

//Underlying network interface
static NetInterface *nicDriverInterface;

//IAR EWARM compiler?
#if defined(__ICCARM__)

//Transmit buffer
#pragma data_alignment = 4
static uint8_t txBuffer[GD32F307_ETH_TX_BUFFER_COUNT][GD32F307_ETH_TX_BUFFER_SIZE];
//Receive buffer
#pragma data_alignment = 4
static uint8_t rxBuffer[GD32F307_ETH_RX_BUFFER_COUNT][GD32F307_ETH_RX_BUFFER_SIZE];
//Transmit DMA descriptors
#pragma data_alignment = 4
static Stm32f2xxTxDmaDesc txDmaDesc[GD32F307_ETH_TX_BUFFER_COUNT];
//Receive DMA descriptors
#pragma data_alignment = 4
static Stm32f2xxRxDmaDesc rxDmaDesc[GD32F307_ETH_RX_BUFFER_COUNT];

//Keil MDK-ARM or GCC compiler?
#else

//Transmit buffer
static uint8_t txBuffer[AT32F437_ETH_TX_BUFFER_COUNT][AT32F437_ETH_TX_BUFFER_SIZE]
   __attribute__((aligned(4)));
//Receive buffer
static uint8_t rxBuffer[AT32F437_ETH_RX_BUFFER_COUNT][AT32F437_ETH_RX_BUFFER_SIZE]
   __attribute__((aligned(4)));
//Transmit DMA descriptors
static emac_dma_desc_type txDmaDesc[AT32F437_ETH_TX_BUFFER_COUNT]
   __attribute__((aligned(4)));
//Receive DMA descriptors
static emac_dma_desc_type rxDmaDesc[AT32F437_ETH_RX_BUFFER_COUNT]
   __attribute__((aligned(4)));

#endif

//Pointer to the current TX DMA descriptor
extern emac_dma_desc_type  *dma_tx_desc_to_set;
//Pointer to the current RX DMA descriptor
extern emac_dma_desc_type  *dma_rx_desc_to_get;

typedef struct{
        u32 length;
        u32 buffer;
        emac_dma_desc_type *descriptor;
}FrameTypeDef;

static emac_control_config_type mac_control_para;

/**
* @brief AT32F437 Ethernet MAC driver
**/

const NicDriver at32f437EthDriver =
{
   NIC_TYPE_ETHERNET,
   ETH_MTU,
   at32f437EthInit,
   at32f437EthTick,
   at32f437EthEnableIrq,
   at32f437EthDisableIrq,
   at32f437EthEventHandler,
   at32f437EthSendPacket,
   at32f437EthUpdateMacAddrFilter,
   at32f437EthUpdateMacConfig,
   at32f437EthWritePhyReg,
   at32f437EthReadPhyReg,
   TRUE,
   TRUE,
   TRUE,
   FALSE
};

/**
  * @brief  this is delay function base on system clock.
  * @param  delay: delay time
  * @retval none
  */
static void emac_delay(uint32_t delay)
{
  __IO uint32_t delay_time = delay * (system_core_clock / 8 / 1000);
  do
  {
    __NOP();
  }
  while(delay_time --);
}

/**
  * @brief  reset layer 1
  * @param  none
  * @retval none
  */
static void reset_phy(void)
{
        gpio_init_type gpio_init_struct = {0};
        crm_periph_clock_enable(CRM_GPIOE_PERIPH_CLOCK, TRUE);
        crm_periph_clock_enable(CRM_GPIOG_PERIPH_CLOCK, TRUE);

        gpio_init_struct.gpio_drive_strength = GPIO_DRIVE_STRENGTH_STRONGER;
        gpio_init_struct.gpio_mode = GPIO_MODE_OUTPUT;
        gpio_init_struct.gpio_out_type = GPIO_OUTPUT_PUSH_PULL;
        gpio_init_struct.gpio_pins = GPIO_PINS_15;
        gpio_init_struct.gpio_pull = GPIO_PULL_NONE;
        gpio_init(GPIOE, &gpio_init_struct);

        gpio_init_struct.gpio_pins = GPIO_PINS_15;
        gpio_init_struct.gpio_pull = GPIO_PULL_NONE;
        gpio_init(GPIOG, &gpio_init_struct);

        /* exit power down mode */
        gpio_bits_reset(GPIOG, GPIO_PINS_15);

        /*reset phy */
        gpio_bits_reset(GPIOE, GPIO_PINS_15);
        emac_delay(2);
        gpio_bits_set(GPIOE, GPIO_PINS_15);
        emac_delay(2);
}

/**
  * @brief  reset phy register
  * @param  none
  * @retval SUCCESS or ERROR
  */
error_status emac_phy_register_reset(void)
{
        uint16_t data = 0;
        uint32_t timeout = 0;
        uint32_t i = 0;

        if(emac_phy_register_write(PHY_ADDRESS, PHY_CONTROL_REG, PHY_RESET_BIT) == ERROR)
        {
                return ERROR;
        }

        for(i = 0; i < 0x0000FFFF; i++);

        do
        {
                timeout++;
                if(emac_phy_register_read(PHY_ADDRESS, PHY_CONTROL_REG, &data) == ERROR)
                {
                        return ERROR;
                }
        } while((data & PHY_RESET_BIT) && (timeout < PHY_TIMEOUT));

        for(i = 0; i < 0x0000FFFF; i++);
        if(timeout == PHY_TIMEOUT)
        {
                return ERROR;
        }
        return SUCCESS;
}


/**
  * @brief  initialize emac phy
  * @param  none
  * @retval SUCCESS or ERROR
  */
error_status emac_phy_init(emac_control_config_type *control_para)
{
        emac_clock_range_set();
        if(emac_phy_register_reset() == ERROR)
        {
        return ERROR;
        }

        emac_control_config(control_para);
        return SUCCESS;
}

/**
  * @brief  configures emac layer2
  * @param  none
  * @retval error or success
  */
error_status emac_layer2_configuration(void)
{
        emac_dma_config_type dma_control_para;
        crm_periph_clock_enable(CRM_SCFG_PERIPH_CLOCK, TRUE);
        #ifdef MII_MODE
        scfg_emac_interface_set(SCFG_EMAC_SELECT_MII);
        #elif defined RMII_MODE
        scfg_emac_interface_set(SCFG_EMAC_SELECT_RMII);
        #endif
        crm_clock_out1_set(CRM_CLKOUT1_PLL);
        crm_clkout_div_set(CRM_CLKOUT_INDEX_1, CRM_CLKOUT_DIV1_5, CRM_CLKOUT_DIV2_2);

        /* reset phy */
        reset_phy();
        /* reset emac ahb bus */
        emac_reset();

        /* software reset emac dma */
        emac_dma_software_reset_set();

        while(emac_dma_software_reset_get() == SET);

        emac_control_para_init(&mac_control_para);

        mac_control_para.auto_nego = EMAC_AUTO_NEGOTIATION_ON;

        if(emac_phy_init(&mac_control_para) == ERROR)
        {
                return ERROR;
        }

        emac_dma_para_init(&dma_control_para);

        dma_control_para.rsf_enable = TRUE;
        dma_control_para.tsf_enable = TRUE;
        dma_control_para.osf_enable = TRUE;
        dma_control_para.aab_enable = TRUE;
        dma_control_para.usp_enable = TRUE;
        dma_control_para.fb_enable = TRUE;
        dma_control_para.flush_rx_disable = TRUE;
        dma_control_para.rx_dma_pal = EMAC_DMA_PBL_32;
        dma_control_para.tx_dma_pal = EMAC_DMA_PBL_32;
        dma_control_para.priority_ratio = EMAC_DMA_1_RX_1_TX;

        emac_dma_config(&dma_control_para);
        emac_dma_interrupt_enable(EMAC_DMA_INTERRUPT_NORMAL_SUMMARY, TRUE);
        emac_dma_interrupt_enable(EMAC_DMA_INTERRUPT_TX, TRUE);
        emac_dma_interrupt_enable(EMAC_DMA_INTERRUPT_RX, TRUE);
//        emac_interrupt_mask_set(EMAC_INTERRUPT_TST_MASK, TRUE);

        return SUCCESS;
}

/*******************************************************************************
* Function Name  : emac_rxpkt_chainmode
* Description    : Receives a packet.
* Input          : None
* Output         : None
* Return         : frame: farme size and location
*******************************************************************************/
FrameTypeDef emac_rxpkt_chainmode(void)
{
        uint32_t framelength = 0;
        FrameTypeDef frame = {0,0};

        /* Check if the descriptor is owned by the ETHERNET DMA (when set) or CPU (when reset) */
        if((dma_rx_desc_to_get->status & EMAC_DMARXDESC_OWN) != (uint32_t)RESET)
        {
                frame.length = FALSE;

                if(emac_dma_flag_get(EMAC_DMA_RBU_FLAG))
                {
                        /* Clear RBUS ETHERNET DMA flag */
                        emac_dma_flag_clear(EMAC_DMA_RBU_FLAG);
                        /* Resume DMA reception */
                        EMAC_DMA->rpd_bit.rpd = FALSE;
                }
                /* Return error: OWN bit set */
                return frame;
        }

        if(((dma_rx_desc_to_get->status & EMAC_DMATXDESC_ES) == (uint32_t)RESET) &&
        ((dma_rx_desc_to_get->status & EMAC_DMARXDESC_LS) != (uint32_t)RESET) &&
        ((dma_rx_desc_to_get->status & EMAC_DMARXDESC_FS) != (uint32_t)RESET))
        {
                /* Get the Frame Length of the received packet: substruct 4 bytes of the CRC */
                framelength = ((dma_rx_desc_to_get->status & EMAC_DMARXDESC_FL) >> EMAC_DMARXDESC_FRAME_LENGTHSHIFT) - 4;

                /* Get the addrees of the actual buffer */
                frame.buffer = dma_rx_desc_to_get->buf1addr;
        }
        else
        {
                /* Return ERROR */
                framelength = FALSE;
        }

        frame.length = framelength;

        frame.descriptor = dma_rx_desc_to_get;

        /* Update the ETHERNET DMA global Rx descriptor with next Rx decriptor */
        /* Chained Mode */
        /* Selects the next DMA Rx descriptor list for next buffer to read */
        dma_rx_desc_to_get = (emac_dma_desc_type*) (dma_rx_desc_to_get->buf2nextdescaddr);
        /* Return Frame */
        return (frame);
}

/*******************************************************************************
* Function Name  : emac_txpkt_chainmode
* Description    : Transmits a packet, from application buffer, pointed by ppkt.
* Input          : - FrameLength: Tx Packet size.
* Output         : None
* Return         : ERROR: in case of Tx desc owned by DMA
*                  SUCCESS: for correct transmission
*******************************************************************************/
error_status emac_txpkt_chainmode(uint16_t FrameLength)
{
        /* Check if the descriptor is owned by the ETHERNET DMA (when set) or CPU (when reset) */
        if((dma_tx_desc_to_set->status & EMAC_DMATXDESC_OWN) != (uint32_t)RESET)
        {
                /* Return ERROR: OWN bit set */
                return ERROR;
        }

        /* Setting the Frame Length: bits[12:0] */
        dma_tx_desc_to_set->controlsize = (FrameLength & EMAC_DMATXDESC_TBS1);

        /* Setting the last segment and first segment bits (in this case a frame is transmitted in one descriptor) */
        dma_tx_desc_to_set->status |= EMAC_DMATXDESC_LS | EMAC_DMATXDESC_FS;

        /* Set Own bit of the Tx descriptor Status: gives the buffer back to ETHERNET DMA */
        dma_tx_desc_to_set->status |= EMAC_DMATXDESC_OWN;
        /* When Tx Buffer unavailable flag is set: clear it and resume transmission */
        if(emac_dma_flag_get(EMAC_DMA_TBU_FLAG))
        {
                /* Clear TBUS ETHERNET DMA flag */
                emac_dma_flag_clear(EMAC_DMA_TBU_FLAG);
                /* Resume DMA transmission*/
                EMAC_DMA->tpd_bit.tpd = 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 */
        dma_tx_desc_to_set = (emac_dma_desc_type*) (dma_tx_desc_to_set->buf2nextdescaddr);
        /* Return SUCCESS */
        return SUCCESS;
}


/*******************************************************************************
* Function Name  : emac_getcurrenttxbuffer
* Description    : Return the address of the buffer pointed by the current descritor.
* Input          : None
* Output         : None
* Return         : Buffer address
*******************************************************************************/
uint32_t emac_getcurrenttxbuffer(void)
{
        /* Return Buffer address */
        return (dma_tx_desc_to_set->buf1addr);
}



/**
* @brief AT32F437 Ethernet MAC initialization
* @param[in] interface Underlying network interface
* @return Error code
**/

error_t at32f437EthInit(NetInterface *interface)
{
        error_t error = NO_ERROR;

        //Debug message
        TRACE_INFO("Initializing AT32F437 Ethernet MAC...\r\n");

        //Save underlying network interface
        nicDriverInterface = interface;
       
        //Enable Ethernet MAC clock
        crm_periph_clock_enable(CRM_EMAC_PERIPH_CLOCK, TRUE);
        crm_periph_clock_enable(CRM_EMACTX_PERIPH_CLOCK, TRUE);
        crm_periph_clock_enable(CRM_EMACRX_PERIPH_CLOCK, TRUE);
       
        //GPIO configuration
        at32f437EthInitGpio(interface);

        //Reset Ethernet MAC peripheral
        crm_periph_reset(CRM_EMAC_PERIPH_RESET, TRUE);
        crm_periph_reset(CRM_EMAC_PERIPH_RESET, FALSE);

//        emac_layer2_configuration();

        emac_dma_config_type dma_control_para;
        crm_periph_clock_enable(CRM_SCFG_PERIPH_CLOCK, TRUE);
        scfg_emac_interface_set(SCFG_EMAC_SELECT_RMII);
        crm_clock_out1_set(CRM_CLKOUT1_PLL);
        crm_clkout_div_set(CRM_CLKOUT_INDEX_1, CRM_CLKOUT_DIV1_5, CRM_CLKOUT_DIV2_2);

        /* reset phy */
        reset_phy();
        /* reset emac ahb bus */
        emac_reset();

        /* software reset emac dma */
        emac_dma_software_reset_set();

        while(emac_dma_software_reset_get() == SET);

        emac_control_para_init(&mac_control_para);

        mac_control_para.auto_nego = EMAC_AUTO_NEGOTIATION_ON;
       
        emac_clock_range_set();

       
//   //Perform a software reset
//   emac_dma_software_reset_set();
//   //Wait for the reset to complete
//   uint32_t tickstart = 0;
//   while(emac_dma_software_reset_get() != RESET)
//   {
//        sleep(10);
//        if((tickstart++) > 500U)
//        {
//            break;
//        }
//   };

   //Adjust MDC clock range depending on HCLK frequency
//   ENET_MAC_PHY_CTL = ENET_MDC_HCLK_DIV62;

        //Valid Ethernet PHY or switch driver?
        if(interface->phyDriver != NULL)
        {
                //Ethernet PHY initialization
                error = interface->phyDriver->init(interface);
        }
        else if(interface->switchDriver != NULL)
        {
                //Ethernet switch initialization
                error = interface->switchDriver->init(interface);
        }
        else
        {
                //The interface is not properly configured
                error = ERROR_FAILURE;
        }

        //Any error to report?
        if(error)
        {
                return error;
        }
       
       

   //Use default MAC configuration
//   ENET_MAC_CFG = ENET_MAC_CFG_ROD;

    //Set the MAC address of the station
        emac_local_address_set(interface->macAddr.b);

//   //The MAC supports 3 additional addresses for unicast perfect filtering
        EMAC->a1l = 0;
        EMAC->a1h = 0;
        EMAC->a2l = 0;
        EMAC->a2h = 0;
        EMAC->a3l = 0;
        EMAC->a3h = 0;

    //Initialize hash table
        emac_hash_table_low32bits_set(0);
    emac_hash_table_high32bits_set(0);

//   //Configure the receive filter
//   ENET_MAC_FRMF = ENET_MAC_FRMF_HPFLT | ENET_MAC_FRMF_HMF;
//   //Disable flow control
//   ENET_MAC_FCTL = 0;
//   //Enable store and forward mode
//   ENET_DMA_CTL = ENET_DMA_CTL_RSFD | ENET_DMA_CTL_TSFD;

//   //Configure DMA bus mode
//   ENET_DMA_BCTL = ENET_DMA_BCTL_AA | ENET_DMA_BCTL_UIP | ENET_RXDP_1BEAT |
//      ENET_ARBITRATION_RXTX_1_1 | ENET_PGBL_1BEAT | ENET_DMA_BCTL_DFM;

        emac_control_config(&mac_control_para);
       
        emac_dma_para_init(&dma_control_para);

        dma_control_para.rsf_enable = TRUE;
        dma_control_para.tsf_enable = TRUE;
        dma_control_para.osf_enable = TRUE;
        dma_control_para.aab_enable = TRUE;
        dma_control_para.usp_enable = TRUE;
        dma_control_para.fb_enable = TRUE;
        dma_control_para.flush_rx_disable = TRUE;
        dma_control_para.rx_dma_pal = EMAC_DMA_PBL_32;
        dma_control_para.tx_dma_pal = EMAC_DMA_PBL_32;
        dma_control_para.priority_ratio = EMAC_DMA_2_RX_1_TX;

        emac_dma_config(&dma_control_para);
        emac_dma_interrupt_enable(EMAC_DMA_INTERRUPT_NORMAL_SUMMARY, TRUE);
        emac_dma_interrupt_enable(EMAC_DMA_INTERRUPT_TX, TRUE);
        emac_dma_interrupt_enable(EMAC_DMA_INTERRUPT_RX, TRUE);

        //Initialize DMA descriptor lists
        at32f437EthInitDmaDesc(interface);
       

//   //Prevent interrupts from being generated when the transmit statistic
//   //counters reach half their maximum value
//   ENET_MSC_TINTMSK = ENET_MSC_TINTMSK_TGFIM | ENET_MSC_TINTMSK_TGFMSCIM |
//      ENET_MSC_TINTMSK_TGFSCIM;

//   //Prevent interrupts from being generated when the receive statistic
//   //counters reach half their maximum value
//   ENET_MSC_RINTMSK = ENET_MSC_RINTMSK_RGUFIM | ENET_MSC_RINTMSK_RFAEIM |
//      ENET_MSC_RINTMSK_RFCEIM;

//   //Disable MAC interrupts
//   ENET_MAC_INTMSK = ENET_MAC_INTMSK_TMSTIM | ENET_MAC_INTMSK_WUMIM;
//   //Enable the desired DMA interrupts
//   ENET_DMA_INTEN = ENET_DMA_INTEN_NIE | ENET_DMA_INTEN_RIE | ENET_DMA_INTEN_TIE;

        //Set priority grouping (4 bits for pre-emption priority, no bits for subpriority)
//        nvic_priority_group_config(AT32F437_ETH_IRQ_PRIORITY_GROUPING);

    //Configure Ethernet interrupt priority
        nvic_irq_enable(EMAC_IRQn, AT32F437_ETH_IRQ_GROUP_PRIORITY, AT32F437_ETH_IRQ_SUB_PRIORITY);

//   //Enable MAC transmission and reception
//   ENET_MAC_CFG |= ENET_MAC_CFG_TEN | ENET_MAC_CFG_REN;
//   //Enable DMA transmission and reception
//   ENET_DMA_CTL |= ENET_DMA_CTL_STE | ENET_DMA_CTL_SRE;

        //Accept any packets from the upper layer
        osSetEvent(&interface->nicTxEvent);

        //Successful initialization
        return NO_ERROR;
}


//AT_START_F437_V1 evaluation board?
#if defined(AT_START_F437_V1)

/**
* @brief GPIO configuration
* @param[in] interface Underlying network interface
**/

void at32f437EthInitGpio(NetInterface *interface)
{
        gpio_init_type gpio_init_struct = {0};

        /* emac pins clock enable */
        crm_periph_clock_enable(CRM_GPIOA_PERIPH_CLOCK, TRUE);
        crm_periph_clock_enable(CRM_GPIOB_PERIPH_CLOCK, TRUE);
        crm_periph_clock_enable(CRM_GPIOC_PERIPH_CLOCK, TRUE);
        crm_periph_clock_enable(CRM_GPIOD_PERIPH_CLOCK, TRUE);
        crm_periph_clock_enable(CRM_GPIOE_PERIPH_CLOCK, TRUE);
        crm_periph_clock_enable(CRM_GPIOG_PERIPH_CLOCK, TRUE);

        /* pa2 -> mdio */
        gpio_pin_mux_config(GPIOA, GPIO_PINS_SOURCE2, GPIO_MUX_11);
        gpio_init_struct.gpio_drive_strength = GPIO_DRIVE_STRENGTH_STRONGER;
        gpio_init_struct.gpio_mode = GPIO_MODE_MUX;
        gpio_init_struct.gpio_out_type = GPIO_OUTPUT_PUSH_PULL;
        gpio_init_struct.gpio_pins = GPIO_PINS_2;
        gpio_init_struct.gpio_pull = GPIO_PULL_NONE;
        gpio_init(GPIOA, &gpio_init_struct);

        /* pc1 -> mdc */
        gpio_pin_mux_config(GPIOC, GPIO_PINS_SOURCE1, GPIO_MUX_11);
        gpio_init_struct.gpio_pins = GPIO_PINS_1;
        gpio_init(GPIOC, &gpio_init_struct);

        #ifdef MII_MODE
        /*
        pb12 -> tx_d0
        pb13 -> tx_d1
        pc2  -> tx_d2
        pb8  -> tx_d3
        pb11 -> tx_en
        pc3  -> tx_clk
        */
        gpio_pin_mux_config(GPIOB, GPIO_PINS_SOURCE8, GPIO_MUX_11);
        gpio_pin_mux_config(GPIOB, GPIO_PINS_SOURCE11, GPIO_MUX_11);
        gpio_pin_mux_config(GPIOB, GPIO_PINS_SOURCE12, GPIO_MUX_11);
        gpio_pin_mux_config(GPIOB, GPIO_PINS_SOURCE13, GPIO_MUX_11);
        gpio_init_struct.gpio_pins = GPIO_PINS_8 | GPIO_PINS_11 | GPIO_PINS_12 | GPIO_PINS_13;
        gpio_init(GPIOB, &gpio_init_struct);

        gpio_pin_mux_config(GPIOC, GPIO_PINS_SOURCE2, GPIO_MUX_11);
        gpio_pin_mux_config(GPIOC, GPIO_PINS_SOURCE3, GPIO_MUX_11);
        gpio_init_struct.gpio_pins = GPIO_PINS_2 | GPIO_PINS_3;
        gpio_init(GPIOC, &gpio_init_struct);

        /*
        pd8  -> rx_dv
        pd9  -> rx_d0
        pd10 -> rx_d1
        pd11 -> rx_d2
        pd12 -> rx_d3
        */
        gpio_pin_mux_config(GPIOD, GPIO_PINS_SOURCE8, GPIO_MUX_11);
        gpio_pin_mux_config(GPIOD, GPIO_PINS_SOURCE9, GPIO_MUX_11);
        gpio_pin_mux_config(GPIOD, GPIO_PINS_SOURCE10, GPIO_MUX_11);
        gpio_pin_mux_config(GPIOD, GPIO_PINS_SOURCE11, GPIO_MUX_11);
        gpio_pin_mux_config(GPIOD, GPIO_PINS_SOURCE12, GPIO_MUX_11);
        gpio_init_struct.gpio_pins = GPIO_PINS_8 | GPIO_PINS_9 | GPIO_PINS_10 | GPIO_PINS_11 | GPIO_PINS_12;
        gpio_init(GPIOD, &gpio_init_struct);

        /*
        pa1  -> rx_clk
        pa0  -> crs
        pa3  -> col
        pb10 -> rx_er
        */
        gpio_pin_mux_config(GPIOA, GPIO_PINS_SOURCE0, GPIO_MUX_11);
        gpio_pin_mux_config(GPIOA, GPIO_PINS_SOURCE1, GPIO_MUX_11);
        gpio_pin_mux_config(GPIOA, GPIO_PINS_SOURCE3, GPIO_MUX_11);
        gpio_init_struct.gpio_pins = GPIO_PINS_0 | GPIO_PINS_1 | GPIO_PINS_3;
        gpio_init(GPIOA, &gpio_init_struct);

        gpio_pin_mux_config(GPIOB, GPIO_PINS_SOURCE10, GPIO_MUX_11);
        gpio_init_struct.gpio_pins = GPIO_PINS_10;
        gpio_init(GPIOB, &gpio_init_struct);
        #endif  /* MII_MODE */

        #ifdef RMII_MODE
        /*
        pb12 -> tx_d0
        pb13 -> tx_d1
        pb11 -> tx_en
        */
        gpio_pin_mux_config(GPIOG, GPIO_PINS_SOURCE11, GPIO_MUX_11);
        gpio_pin_mux_config(GPIOG, GPIO_PINS_SOURCE13, GPIO_MUX_11);
        gpio_pin_mux_config(GPIOG, GPIO_PINS_SOURCE14, GPIO_MUX_11);
        gpio_init_struct.gpio_pins = GPIO_PINS_11 | GPIO_PINS_13 | GPIO_PINS_14;
        gpio_init(GPIOG, &gpio_init_struct);

        /*
        pd8  -> rx_dv
        pd9  -> rx_d0
        pd10 -> rx_d1
        */
        gpio_pin_mux_config(GPIOD, GPIO_PINS_SOURCE8, GPIO_MUX_11);
        gpio_pin_mux_config(GPIOD, GPIO_PINS_SOURCE9, GPIO_MUX_11);
        gpio_pin_mux_config(GPIOD, GPIO_PINS_SOURCE10, GPIO_MUX_11);
        gpio_init_struct.gpio_pins = GPIO_PINS_8 | GPIO_PINS_9 | GPIO_PINS_10;
        gpio_init_struct.gpio_mode = GPIO_MODE_MUX;
        gpio_init(GPIOD, &gpio_init_struct);


        #endif  /* RMII_MODE */
        /*
        pa1  -> ref_clk
        */
        gpio_pin_mux_config(GPIOA, GPIO_PINS_SOURCE1, GPIO_MUX_11);
        gpio_init_struct.gpio_pins = GPIO_PINS_1;
        gpio_init(GPIOA, &gpio_init_struct);

        #if !CRYSTAL_ON_PHY
        gpio_pin_mux_config(GPIOA, GPIO_PINS_SOURCE8, GPIO_MUX_0);
        gpio_init_struct.gpio_pins = GPIO_PINS_8;
        gpio_init_struct.gpio_mode = GPIO_MODE_MUX;
        gpio_init(GPIOA, &gpio_init_struct);
        #endif
}

#endif


/**
* @brief Initialize DMA descriptor lists
* @param[in] interface Underlying network interface
**/

void at32f437EthInitDmaDesc(NetInterface *interface)
{
        /* Initialize Tx Descriptors list: Chain Mode */
        emac_dma_descriptor_list_address_set(EMAC_DMA_TRANSMIT, txDmaDesc, &txBuffer[0][0], AT32F437_ETH_TX_BUFFER_COUNT);
        /* Initialize Rx Descriptors list: Chain Mode  */
        emac_dma_descriptor_list_address_set(EMAC_DMA_RECEIVE, rxDmaDesc, &rxBuffer[0][0], AT32F437_ETH_RX_BUFFER_COUNT);

        /* Enable Ethernet Rx interrrupt */
        {
                int i;
                for(i = 0; i < AT32F437_ETH_RX_BUFFER_COUNT; i++)
                {
                        emac_dma_rx_desc_interrupt_config(&rxDmaDesc, TRUE);
                }
#ifdef CHECKSUM_BY_HARDWARE
                for(i = 0; i < AT32F437_ETH_TX_BUFFER_COUNT; i++)
                {
                        txDmaDesc.status |= EMAC_DMATXDESC_CIC_TUI_FULL | EMAC_DMATXDESC_IC;
                }
#endif
        }
       
        /* Enable MAC and DMA transmission and reception */
        emac_start();
}


/**
* @brief AT32F437 Ethernet MAC timer handler
*
* This routine is periodically called by the TCP/IP stack to handle periodic
* operations such as polling the link state
*
* @param[in] interface Underlying network interface
**/

void at32f437EthTick(NetInterface *interface)
{
        //Handle periodic operations
        interface->phyDriver->tick(interface);
}


/**
* @brief Enable interrupts
* @param[in] interface Underlying network interface
**/

void at32f437EthEnableIrq(NetInterface *interface)
{
        //Enable Ethernet MAC interrupts
        NVIC_EnableIRQ(EMAC_IRQn);
       
        /* enable mac and dma transmission and reception */
//    emac_start();

        //Enable Ethernet PHY interrupts
        interface->phyDriver->enableIrq(interface);
}


/**
* @brief Disable interrupts
* @param[in] interface Underlying network interface
**/

void at32f437EthDisableIrq(NetInterface *interface)
{
        //Disable Ethernet MAC interrupts
        NVIC_DisableIRQ(EMAC_IRQn);
       
        /* disable mac and dma transmission and reception */
//    emac_stop();

        //Disable Ethernet PHY interrupts
        interface->phyDriver->disableIrq(interface);
}


/**
* @brief AT32F437 Ethernet MAC interrupt service routine
**/

void EMAC_IRQHandler(void)
{
        bool_t flag;
        uint32_t status;

        //Interrupt service routine prologue
        osEnterIsr();

        //This flag will be set if a higher priority task must be woken
        flag = FALSE;

        //Read DMA status register
        //Packet transmitted?
        if (emac_dma_flag_get(EMAC_DMA_TI_FLAG) != RESET)
        {
                emac_dma_flag_clear(EMAC_DMA_TI_FLAG);
               
                //Check whether the TX buffer is available for writing
//                if(emac_dma_flag_get(EMAC_DMA_TBU_FLAG) == RESET)
                {
                        //Notify the TCP/IP stack that the transmitter is ready to send
                        flag |= osSetEventFromIsr(&nicDriverInterface->nicTxEvent);
                }
        }
       
        //Read DMA status register
        //Packet received?
        if (emac_dma_flag_get(EMAC_DMA_RI_FLAG) != RESET)
        {
                emac_dma_flag_clear(EMAC_DMA_RI_FLAG);
               
                //Set event flag
                nicDriverInterface->nicEvent = TRUE;
                //Notify the TCP/IP stack of the event
                flag |= osSetEventFromIsr(&netEvent);
        }

        //Clear NIS interrupt flag
        emac_dma_flag_clear(EMAC_DMA_NIS_FLAG);

        //Interrupt service routine epilogue
        osExitIsr(flag);
}


/**
* @brief AT32F437 Ethernet MAC event handler
* @param[in] interface Underlying network interface
**/

void at32f437EthEventHandler(NetInterface *interface)
{
        error_t error;

        //Packet received?
        if (emac_dma_flag_get(EMAC_DMA_RI_FLAG) != RESET)
        {
                //Clear interrupt flag
                emac_dma_flag_clear(EMAC_DMA_RI_FLAG);
       
                //Process all pending packets
                do
                {
                        //Read incoming packet
                        error = at32f437EthReceivePacket(interface);

                //No more data in the receive buffer?
                } while(error != ERROR_BUFFER_EMPTY);
        }
       
        //Re-enable DMA interrupts
        emac_dma_interrupt_enable(EMAC_DMA_INTERRUPT_NORMAL_SUMMARY, TRUE);
        emac_dma_interrupt_enable(EMAC_DMA_INTERRUPT_TX, TRUE);
        emac_dma_interrupt_enable(EMAC_DMA_INTERRUPT_RX, TRUE);
       
}


/**
* @brief Send a packet
* @param[in] interface Underlying network interface
* @param[in] buffer Multi-part buffer containing the data to send
* @param[in] offset Offset to the first data byte
* @param[in] ancillary Additional options passed to the stack along with
*   the packet
* @return Error code
**/

error_t at32f437EthSendPacket(NetInterface *interface,
   const NetBuffer *buffer, size_t offset, NetTxAncillary *ancillary)
{
        size_t length;

        uint8_t *tx_buffer =  (uint8_t *)emac_getcurrenttxbuffer();

        //Retrieve the length of the packet
        length = netBufferGetLength(buffer) - offset;

        //Check the frame length
        if(length > AT32F437_ETH_TX_BUFFER_SIZE)
        {
                //The transmitter can accept another packet
                osSetEvent(&interface->nicTxEvent);
                //Report an error
                return ERROR_INVALID_LENGTH;
        }

//        //Make sure the current buffer is available for writing
//        if(emac_dma_flag_get(EMAC_DMA_TBU_FLAG))
//        {
//                /* Clear TBUS ETHERNET DMA flag */
//                emac_dma_flag_clear(EMAC_DMA_TBU_FLAG);
//                /* Resume DMA transmission*/
//                EMAC_DMA->tpd_bit.tpd = 0;
//               
//                return ERROR_FAILURE;
//        }

        //Copy user data to the transmit buffer
        netBufferRead((uint8_t *) tx_buffer, buffer, offset, length);

        if(emac_txpkt_chainmode(length) == ERROR)
        {
                return ERROR_FAILURE;
        }
        //The transmitter can accept another packet
        osSetEvent(&interface->nicTxEvent);

        //Data successfully written
        return NO_ERROR;
}


/**
* @brief Receive a packet
* @param[in] interface Underlying network interface
* @return Error code
**/

error_t at32f437EthReceivePacket(NetInterface *interface)
{
   error_t error;
   size_t n;
   NetRxAncillary ancillary;
   FrameTypeDef frame;
       
        while(emac_received_packet_size_get() != 0)
        {
                frame = emac_rxpkt_chainmode();
                if (frame.length > 0)
                {
                        //Limit the number of data to read
                        n = MIN(frame.length, AT32F437_ETH_RX_BUFFER_SIZE);
                        //Additional options can be passed to the stack along with the packet
                        ancillary = NET_DEFAULT_RX_ANCILLARY;

                        //Pass the packet to the upper layer
                        nicProcessPacket(interface, (uint8_t *) frame.buffer, n,
                           &ancillary);

                        //Valid packet received
                        error = NO_ERROR;
                }
                else
                {
                        //The packet is not valid
                        error = ERROR_INVALID_PACKET;
                }
               
                /* Set Own bit of the Rx descriptor Status: gives the buffer back to ETHERNET DMA */
                frame.descriptor->status |= EMAC_DMARXDESC_OWN;

                /* When Rx Buffer unavailable flag is set: clear it and resume reception */
                if(emac_dma_flag_get(EMAC_DMA_RBU_FLAG))
                {
                        /* Clear RBUS ETHERNET DMA flag */
                        emac_dma_flag_clear(EMAC_DMA_RBU_FLAG);
                        /* Resume DMA reception */
                        EMAC_DMA->rpd_bit.rpd = FALSE;
                }
        }

        //Return status code
    return error;
}


/**
* @brief Configure MAC address filtering
* @param[in] interface Underlying network interface
* @return Error code
**/

error_t at32f437EthUpdateMacAddrFilter(NetInterface *interface)
{
   uint_t i;
   uint_t j;
   uint_t k;
   uint32_t crc;
   uint32_t hashTable[2];
   MacAddr unicastMacAddr[3];
   MacFilterEntry *entry;

   //Debug message
   TRACE_DEBUG("Updating MAC filter...\r\n");

   //Set the MAC address of the station
   emac_local_address_set(interface->macAddr.b);
//   ENET_MAC_ADDR0L = interface->macAddr.w[0] | (interface->macAddr.w[1] << 16);
//   ENET_MAC_ADDR0H = interface->macAddr.w[2] | ENET_MAC_ADDR0H_MO;

   //The MAC supports 3 additional addresses for unicast perfect filtering
   unicastMacAddr[0] = MAC_UNSPECIFIED_ADDR;
   unicastMacAddr[1] = MAC_UNSPECIFIED_ADDR;
   unicastMacAddr[2] = MAC_UNSPECIFIED_ADDR;

   //The hash table is used for multicast address filtering
   hashTable[0] = 0;
   hashTable[1] = 0;

   //The MAC address filter contains the list of MAC addresses to accept
   //when receiving an Ethernet frame
   for(i = 0, j = 0; i < MAC_ADDR_FILTER_SIZE; i++)
   {
      //Point to the current entry
      entry = &interface->macAddrFilter;

      //Valid entry?
      if(entry->refCount > 0)
      {
         //Multicast address?
         if(macIsMulticastAddr(&entry->addr))
         {
            //Compute CRC over the current MAC address
            crc = at32f437EthCalcCrc(&entry->addr, sizeof(MacAddr));

            //The upper 6 bits in the CRC register are used to index the
            //contents of the hash table
            k = (crc >> 26) & 0x3F;

            //Update hash table contents
            hashTable[k / 32] |= (1 << (k % 32));
         }
         else
         {
            //Up to 3 additional MAC addresses can be specified
            if(j < 3)
            {
               //Save the unicast address
               unicastMacAddr[j++] = entry->addr;
            }
         }
      }
   }

   //Configure the first unicast address filter
   if(j >= 1)
   {
      //When the AE bit is set, the entry is used for perfect filtering
          //emac_address_filter_set(EMAC_ADDRESS_FILTER_1, EMAC_SOURCE_FILTER, , TRUE);
      //ENET_MAC_ADDR1L = unicastMacAddr[0].w[0] | (unicastMacAddr[0].w[1] << 16);
      //ENET_MAC_ADDR1H = unicastMacAddr[0].w[2] | ENET_MAC_ADDR1H_AFE;
   }
   else
   {
      //When the AE bit is cleared, the entry is ignored
      //ENET_MAC_ADDR1L = 0;
      //ENET_MAC_ADDR1H = 0;
           EMAC->a1l = 0;
           EMAC->a1h = 0;
          
   }

   //Configure the second unicast address filter
   if(j >= 2)
   {
      //When the AE bit is set, the entry is used for perfect filtering
      //ENET_MAC_ADDR2L = unicastMacAddr[1].w[0] | (unicastMacAddr[1].w[1] << 16);
      //ENET_MAC_ADDR2H = unicastMacAddr[1].w[2] | ENET_MAC_ADDR2H_AFE;
   }
   else
   {
      //When the AE bit is cleared, the entry is ignored
      //ENET_MAC_ADDR2L = 0;
      //ENET_MAC_ADDR2H = 0;
           EMAC->a2l = 0;
           EMAC->a2h = 0;
   }

   //Configure the third unicast address filter
   if(j >= 3)
   {
      //When the AE bit is set, the entry is used for perfect filtering
      //ENET_MAC_ADDR3L = unicastMacAddr[2].w[0] | (unicastMacAddr[2].w[1] << 16);
      //ENET_MAC_ADDR3H = unicastMacAddr[2].w[2] | ENET_MAC_ADDR3H_AFE;
   }
   else
   {
      //When the AE bit is cleared, the entry is ignored
      //ENET_MAC_ADDR3L = 0;
      //ENET_MAC_ADDR3H = 0;
           EMAC->a3l = 0;
           EMAC->a3h = 0;
   }

   //Configure the multicast hash table
   emac_hash_table_low32bits_set(hashTable[0]);
   emac_hash_table_high32bits_set(hashTable[1]);

   //Debug message
   TRACE_DEBUG("  ENET_MAC_HLL = %08" PRIX32 "\r\n", EMAC->hth_bit.htl);
   TRACE_DEBUG("  ENET_MAC_HLH = %08" PRIX32 "\r\n", EMAC->hth_bit.hth);

   //Successful processing
   return NO_ERROR;
}


/**
* @brief Adjust MAC configuration parameters for proper operation
* @param[in] interface Underlying network interface
* @return Error code
**/

error_t at32f437EthUpdateMacConfig(NetInterface *interface)
{
        //10BASE-T or 100BASE-TX operation mode?
        if(interface->linkSpeed == NIC_LINK_SPEED_100MBPS)
        {
                emac_fast_speed_set(EMAC_SPEED_100MBPS);
        }
        else
        {
                emac_fast_speed_set(EMAC_SPEED_10MBPS);
                //emac_fast_speed_set(EMAC_SPEED_100MBPS);
        }

        //Half-duplex or full-duplex mode?
        if(interface->duplexMode == NIC_FULL_DUPLEX_MODE)
        {
                emac_duplex_mode_set(EMAC_FULL_DUPLEX);
        }
        else
        {
                emac_duplex_mode_set(EMAC_HALF_DUPLEX);
        }
       
       

        //Successful processing
        return NO_ERROR;
}


/**
* @brief Write PHY register
* @param[in] opcode Access type (2 bits)
* @param[in] phyAddr PHY address (5 bits)
* @param[in] regAddr Register address (5 bits)
* @param[in] data Register value
**/

void at32f437EthWritePhyReg(uint8_t opcode, uint8_t phyAddr,
   uint8_t regAddr, uint16_t data)
{
   uint32_t temp;

   //Valid opcode?
   if(opcode == SMI_OPCODE_WRITE)
   {
           emac_phy_register_write(phyAddr, regAddr, data);
   }
   else
   {
      //The MAC peripheral only supports standard Clause 22 opcodes
   }
}


/**
* @brief Read PHY register
* @param[in] opcode Access type (2 bits)
* @param[in] phyAddr PHY address (5 bits)
* @param[in] regAddr Register address (5 bits)
* @return Register value
**/

uint16_t at32f437EthReadPhyReg(uint8_t opcode, uint8_t phyAddr,
   uint8_t regAddr)
{
   uint16_t data;
   uint32_t temp;

   //Valid opcode?
   if(opcode == SMI_OPCODE_READ)
   {
           emac_phy_register_read(phyAddr, regAddr, &data);
   }
   else
   {
      //The MAC peripheral only supports standard Clause 22 opcodes
      data = 0;
   }

   //Return the value of the PHY register
   return data;
}


/**
* @brief CRC calculation
* @param[in] data Pointer to the data over which to calculate the CRC
* @param[in] length Number of bytes to process
* @return Resulting CRC value
**/

uint32_t at32f437EthCalcCrc(const void *data, size_t length)
{
   uint_t i;
   uint_t j;
   uint32_t crc;
   const uint8_t *p;

   //Point to the data over which to calculate the CRC
   p = (uint8_t *) data;
   //CRC preset value
   crc = 0xFFFFFFFF;

   //Loop through data
   for(i = 0; i < length; i++)
   {
      //The message is processed bit by bit
      for(j = 0; j < 8; j++)
      {
         //Update CRC value
         if((((crc >> 31) ^ (p >> j)) & 0x01) != 0)
         {
            crc = (crc << 1) ^ 0x04C11DB7;
         }
         else
         {
            crc = crc << 1;
         }
      }
   }

   //Return CRC value
   return ~crc;
}



at32f437_eth_driver.h源代码

/**
* @file at32f437_eth_driver.h
* @brief AT32F437 Ethernet MAC driver
*
* @section License
*
* Copyright (C) 2010-2022 Oryx Embedded SARL. All rights reserved.
*
* This file is part of CycloneTCP Eval.
*
* This software is provided in source form for a short-term evaluation only. The
* evaluation license expires 90 days after the date you first download the software.
*
* If you plan to use this software in a commercial product, you are required to
* purchase a commercial license from Oryx Embedded SARL.
*
* After the 90-day evaluation period, you agree to either purchase a commercial
* license or delete all copies of this software. If you wish to extend the
* evaluation period, you must contact sales@oryx-embedded.com.
*
* This evaluation software is provided "as is" without warranty of any kind.
* Technical support is available as an option during the evaluation period.
*
* @author Oryx Embedded SARL (www.oryx-embedded.com)
* @version 2.1.8
**/

#ifndef _AT32F437_ETH_DRIVER_H
#define _AT32F437_ETH_DRIVER_H

//Dependencies
#include "core/nic.h"

//Number of TX buffers
#ifndef AT32F437_ETH_TX_BUFFER_COUNT
   #define AT32F437_ETH_TX_BUFFER_COUNT 6
#elif (AT32F437_ETH_TX_BUFFER_COUNT < 1)
   #error AT32F437_ETH_TX_BUFFER_COUNT parameter is not valid
#endif

//TX buffer size
#ifndef AT32F437_ETH_TX_BUFFER_SIZE
   #define AT32F437_ETH_TX_BUFFER_SIZE 1536
#elif (AT32F437_ETH_TX_BUFFER_SIZE != 1536)
   #error AT32F437_ETH_TX_BUFFER_SIZE parameter is not valid
#endif

//Number of RX buffers
#ifndef AT32F437_ETH_RX_BUFFER_COUNT
   #define AT32F437_ETH_RX_BUFFER_COUNT 6
#elif (AT32F437_ETH_RX_BUFFER_COUNT < 1)
   #error AT32F437_ETH_RX_BUFFER_COUNT parameter is not valid
#endif

//RX buffer size
#ifndef AT32F437_ETH_RX_BUFFER_SIZE
   #define AT32F437_ETH_RX_BUFFER_SIZE 1536
#elif (AT32F437_ETH_RX_BUFFER_SIZE != 1536)
   #error AT32F437_ETH_RX_BUFFER_SIZE parameter is not valid
#endif

//Interrupt priority grouping
#ifndef AT32F437_ETH_IRQ_PRIORITY_GROUPING
   #define AT32F437_ETH_IRQ_PRIORITY_GROUPING 3
#elif (AT32F437_ETH_IRQ_PRIORITY_GROUPING < 0)
   #error AT32F437_ETH_IRQ_PRIORITY_GROUPING parameter is not valid
#endif

//Ethernet interrupt group priority
#ifndef AT32F437_ETH_IRQ_GROUP_PRIORITY
   #define AT32F437_ETH_IRQ_GROUP_PRIORITY 4
#elif (AT32F437_ETH_IRQ_GROUP_PRIORITY < 0)
   #error AT32F437_ETH_IRQ_GROUP_PRIORITY parameter is not valid
#endif

//Ethernet interrupt subpriority
#ifndef AT32F437_ETH_IRQ_SUB_PRIORITY
   #define AT32F437_ETH_IRQ_SUB_PRIORITY 0
#elif (AT32F437_ETH_IRQ_SUB_PRIORITY < 0)
   #error AT32F437_ETH_IRQ_SUB_PRIORITY parameter is not valid
#endif

#define RMII_MODE

//C++ guard
#ifdef __cplusplus
extern "C" {
#endif


//AT32F437 Ethernet MAC driver
extern const NicDriver at32f437EthDriver;

//AT32F437 Ethernet MAC related functions
error_t at32f437EthInit(NetInterface *interface);
void at32f437EthInitGpio(NetInterface *interface);
void at32f437EthInitDmaDesc(NetInterface *interface);

void at32f437EthTick(NetInterface *interface);

void at32f437EthEnableIrq(NetInterface *interface);
void at32f437EthDisableIrq(NetInterface *interface);
void at32f437EthEventHandler(NetInterface *interface);

error_t at32f437EthSendPacket(NetInterface *interface,
   const NetBuffer *buffer, size_t offset, NetTxAncillary *ancillary);

error_t at32f437EthReceivePacket(NetInterface *interface);

error_t at32f437EthUpdateMacAddrFilter(NetInterface *interface);
error_t at32f437EthUpdateMacConfig(NetInterface *interface);

void at32f437EthWritePhyReg(uint8_t opcode, uint8_t phyAddr,
   uint8_t regAddr, uint16_t data);

uint16_t at32f437EthReadPhyReg(uint8_t opcode, uint8_t phyAddr,
   uint8_t regAddr);

uint32_t at32f437EthCalcCrc(const void *data, size_t length);

//C++ guard
#ifdef __cplusplus
}
#endif

#endif



dm9162_driver.c源代码

/**
* @file dm9162_driver.c
* @brief DM9162 Ethernet PHY driver
*
* @section License
*
* Copyright (C) 2010-2022 Oryx Embedded SARL. All rights reserved.
*
* This file is part of CycloneTCP Eval.
*
* This software is provided in source form for a short-term evaluation only. The
* evaluation license expires 90 days after the date you first download the software.
*
* If you plan to use this software in a commercial product, you are required to
* purchase a commercial license from Oryx Embedded SARL.
*
* After the 90-day evaluation period, you agree to either purchase a commercial
* license or delete all copies of this software. If you wish to extend the
* evaluation period, you must contact sales@oryx-embedded.com.
*
* This evaluation software is provided "as is" without warranty of any kind.
* Technical support is available as an option during the evaluation period.
*
* @author Oryx Embedded SARL (www.oryx-embedded.com)
* @version 2.1.8
**/

//Switch to the appropriate trace level
#define TRACE_LEVEL NIC_TRACE_LEVEL

//Dependencies
#include "core/net.h"
#include "drivers/phy/dm9162_driver.h"
#include "debug.h"


/**
* @brief DM9162 Ethernet PHY driver
**/

const PhyDriver dm9162PhyDriver =
{
   dm9162Init,
   dm9162Tick,
   dm9162EnableIrq,
   dm9162DisableIrq,
   dm9162EventHandler
};


/**
* @brief DM9162 PHY transceiver initialization
* @param[in] interface Underlying network interface
* @return Error code
**/

error_t dm9162Init(NetInterface *interface)
{
   //Debug message
   TRACE_INFO("Initializing DM9162...\r\n");

   //Undefined PHY address?
   if(interface->phyAddr >= 32)
   {
      //Use the default address
      interface->phyAddr = DM9162_PHY_ADDR;
   }

   //Initialize serial management interface
   if(interface->smiDriver != NULL)
   {
      interface->smiDriver->init();
   }

   //Initialize external interrupt line driver
   if(interface->extIntDriver != NULL)
   {
      interface->extIntDriver->init();
   }

   //Reset PHY transceiver
   dm9162WritePhyReg(interface, DM9162_BMCR, DM9162_BMCR_RESET);

   //Wait for the reset to complete
   while(dm9162ReadPhyReg(interface, DM9162_BMCR) & DM9162_BMCR_RESET)
   {
   }

//   #if 0 //100M
//   dm9162WritePhyReg(interface, DM9162_BMCR, DM9162_BMCR_SPEED_SEL);
//   #else
//   
//   dm9162WritePhyReg(interface, DM9162_BMCR, DM9162_BMCR_AN_EN);
//   for (uint32_t i = 0; i < 0x100000; i++)
//   {
//           uint16_t data = dm9162ReadPhyReg(interface, DM9162_BMSR);
//           if (data & DM9162_BMSR_AN_COMPLETE)
//           {
//                   TRACE_INFO("Auto-Negotiation Complete.\r\n");
//                   break;
//           }
//   }
//   #endif

   //Dump PHY registers for debugging purpose
   dm9162DumpPhyReg(interface);

   //The PHY will generate interrupts when link status changes are detected
   dm9162WritePhyReg(interface, DM9162_MDINTR, ~(DM9162_MDINTR_LINK_MASK |
      DM9162_MDINTR_INTR_MASK));

   //Force the TCP/IP stack to poll the link state at startup
   interface->phyEvent = TRUE;
   //Notify the TCP/IP stack of the event
   osSetEvent(&netEvent);

   //Successful initialization
   return NO_ERROR;
}


/**
* @brief DM9162 timer handler
* @param[in] interface Underlying network interface
**/

void dm9162Tick(NetInterface *interface)
{
   uint16_t value;
   bool_t linkState;

   //No external interrupt line driver?
   if(interface->extIntDriver == NULL)
   {
      //Read basic status register
      value = dm9162ReadPhyReg(interface, DM9162_BMSR);
      //Retrieve current link state
      linkState = (value & DM9162_BMSR_LINK_STATUS) ? TRUE : FALSE;

      //Link up event?
      if(linkState && !interface->linkState)
      {
         //Set event flag
         interface->phyEvent = TRUE;
         //Notify the TCP/IP stack of the event
         osSetEvent(&netEvent);
      }
      //Link down event?
      else if(!linkState && interface->linkState)
      {
         //Set event flag
         interface->phyEvent = TRUE;
         //Notify the TCP/IP stack of the event
         osSetEvent(&netEvent);
      }
   }
}


/**
* @brief Enable interrupts
* @param[in] interface Underlying network interface
**/

void dm9162EnableIrq(NetInterface *interface)
{
   //Enable PHY transceiver interrupts
   if(interface->extIntDriver != NULL)
   {
      interface->extIntDriver->enableIrq();
   }
}


/**
* @brief Disable interrupts
* @param[in] interface Underlying network interface
**/

void dm9162DisableIrq(NetInterface *interface)
{
   //Disable PHY transceiver interrupts
   if(interface->extIntDriver != NULL)
   {
      interface->extIntDriver->disableIrq();
   }
}


/**
* @brief DM9162 event handler
* @param[in] interface Underlying network interface
**/

void dm9162EventHandler(NetInterface *interface)
{
   uint16_t value;
   bool_t end;

   //Read status register to acknowledge the interrupt
   value = dm9162ReadPhyReg(interface, DM9162_MDINTR);

   //Link status change?
   if((value & DM9162_MDINTR_LINK_CHANGE) != 0)
   {
      //Any link failure condition is latched in the BMSR register. Reading
      //the register twice will always return the actual link status
      value = dm9162ReadPhyReg(interface, DM9162_BMSR);
      value = dm9162ReadPhyReg(interface, DM9162_BMSR);

      //Link is up?
      if((value & DM9162_BMSR_LINK_STATUS) != 0)
      {
         //Wait for the auto-negotiation to complete
         do
         {
            //Read DSCSR register
            value = dm9162ReadPhyReg(interface, DM9162_DSCSR);

            //Check current state
            switch(value & DM9162_DSCSR_ANMB)
            {
            //Auto-negotiation is still in progress?
            case DM9162_DSCSR_ANMB_ABILITY_MATCH:
            case DM9162_DSCSR_ANMB_ACK_MATCH:
            case DM9162_DSCSR_ANMB_CONSIST_MATCH:
            case DM9162_DSCSR_ANMB_LINK_READY:
               end = FALSE;
               break;
            //Auto-negotiation is complete?
            default:
               end = TRUE;
               break;
            }

            //Check loop condition variable
         } while(!end);

         //Read DSCSR register
         value = dm9162ReadPhyReg(interface, DM9162_DSCSR);

         //Check current operation mode
         if((value & DM9162_DSCSR_10HDX) != 0)
         {
            //10BASE-T half-duplex
            interface->linkSpeed = NIC_LINK_SPEED_10MBPS;
            interface->duplexMode = NIC_HALF_DUPLEX_MODE;
         }
         else if((value & DM9162_DSCSR_10FDX) != 0)
         {
            //10BASE-T full-duplex
            interface->linkSpeed = NIC_LINK_SPEED_10MBPS;
            interface->duplexMode = NIC_FULL_DUPLEX_MODE;
         }
         else if((value & DM9162_DSCSR_100HDX) != 0)
         {
            //100BASE-TX half-duplex
            interface->linkSpeed = NIC_LINK_SPEED_100MBPS;
            interface->duplexMode = NIC_HALF_DUPLEX_MODE;
         }
         else if((value & DM9162_DSCSR_100FDX) != 0)
         {
            //100BASE-TX full-duplex
            interface->linkSpeed = NIC_LINK_SPEED_100MBPS;
            interface->duplexMode = NIC_FULL_DUPLEX_MODE;
         }
         else
         {
            //Debug message
            TRACE_WARNING("Invalid operation mode!\r\n");
         }

         //Update link state
         interface->linkState = TRUE;

         //Adjust MAC configuration parameters for proper operation
         interface->nicDriver->updateMacConfig(interface);
      }
      else
      {
         //Update link state
         interface->linkState = FALSE;
      }

      //Process link state change event
      nicNotifyLinkChange(interface);
   }
}


/**
* @brief Write PHY register
* @param[in] interface Underlying network interface
* @param[in] address PHY register address
* @param[in] data Register value
**/

void dm9162WritePhyReg(NetInterface *interface, uint8_t address,
   uint16_t data)
{
   //Write the specified PHY register
   if(interface->smiDriver != NULL)
   {
      interface->smiDriver->writePhyReg(SMI_OPCODE_WRITE,
         interface->phyAddr, address, data);
   }
   else
   {
      interface->nicDriver->writePhyReg(SMI_OPCODE_WRITE,
         interface->phyAddr, address, data);
   }
}


/**
* @brief Read PHY register
* @param[in] interface Underlying network interface
* @param[in] address PHY register address
* @return Register value
**/

uint16_t dm9162ReadPhyReg(NetInterface *interface, uint8_t address)
{
   uint16_t data;

   //Read the specified PHY register
   if(interface->smiDriver != NULL)
   {
      data = interface->smiDriver->readPhyReg(SMI_OPCODE_READ,
         interface->phyAddr, address);
   }
   else
   {
      data = interface->nicDriver->readPhyReg(SMI_OPCODE_READ,
         interface->phyAddr, address);
   }

   //Return the value of the PHY register
   return data;
}


/**
* @brief Dump PHY registers for debugging purpose
* @param[in] interface Underlying network interface
**/

void dm9162DumpPhyReg(NetInterface *interface)
{
   uint8_t i;

   //Loop through PHY registers
   for(i = 0; i < 32; i++)
   {
      //Display current PHY register
      TRACE_DEBUG("%02" PRIu8 ": 0x%04" PRIX16 "\r\n", i,
         dm9162ReadPhyReg(interface, i));
   }

   //Terminate with a line feed
   TRACE_DEBUG("\r\n");
}



dm9162_driver.h源代码

/**
* @file dm9162_driver.h
* @brief DM9162 Ethernet PHY driver
*
* @section License
*
* Copyright (C) 2010-2022 Oryx Embedded SARL. All rights reserved.
*
* This file is part of CycloneTCP Eval.
*
* This software is provided in source form for a short-term evaluation only. The
* evaluation license expires 90 days after the date you first download the software.
*
* If you plan to use this software in a commercial product, you are required to
* purchase a commercial license from Oryx Embedded SARL.
*
* After the 90-day evaluation period, you agree to either purchase a commercial
* license or delete all copies of this software. If you wish to extend the
* evaluation period, you must contact sales@oryx-embedded.com.
*
* This evaluation software is provided "as is" without warranty of any kind.
* Technical support is available as an option during the evaluation period.
*
* @author Oryx Embedded SARL (www.oryx-embedded.com)
* @version 2.1.8
**/

#ifndef _DM9162_DRIVER_H
#define _DM9162_DRIVER_H

//Dependencies
#include "core/nic.h"

//PHY address
#ifndef DM9162_PHY_ADDR
   #define DM9162_PHY_ADDR 3
#elif (DM9162_PHY_ADDR < 0 || DM9162_PHY_ADDR > 31)
   #error DM9162_PHY_ADDR parameter is not valid
#endif

//DM9162 PHY registers
#define DM9162_BMCR                          0x00
#define DM9162_BMSR                          0x01
#define DM9162_PHYID1                        0x02
#define DM9162_PHYID2                        0x03
#define DM9162_ANAR                          0x04
#define DM9162_ANLPAR                        0x05
#define DM9162_ANER                          0x06
#define DM9162_DSCR                          0x10
#define DM9162_DSCSR                         0x11
#define DM9162_10BTCSR                       0x12
#define DM9162_MDINTR                        0x15
#define DM9162_RECR                          0x16
#define DM9162_DISCR                         0x17
#define DM9162_RLSR                          0x18

//Basic Mode Control register
#define DM9162_BMCR_RESET                    0x8000
#define DM9162_BMCR_LOOPBACK                 0x4000
#define DM9162_BMCR_SPEED_SEL                0x2000
#define DM9162_BMCR_AN_EN                    0x1000
#define DM9162_BMCR_POWER_DOWN               0x0800
#define DM9162_BMCR_ISOLATE                  0x0400
#define DM9162_BMCR_RESTART_AN               0x0200
#define DM9162_BMCR_DUPLEX_MODE              0x0100
#define DM9162_BMCR_COL_TEST                 0x0080

//Basic Mode Status register
#define DM9162_BMSR_100BT4                   0x8000
#define DM9162_BMSR_100BTX_FD                0x4000
#define DM9162_BMSR_100BTX_HD                0x2000
#define DM9162_BMSR_10BT_FD                  0x1000
#define DM9162_BMSR_10BT_HD                  0x0800
#define DM9162_BMSR_MF_PREAMBLE_SUPPR        0x0040
#define DM9162_BMSR_AN_COMPLETE              0x0020
#define DM9162_BMSR_REMOTE_FAULT             0x0010
#define DM9162_BMSR_AN_CAPABLE               0x0008
#define DM9162_BMSR_LINK_STATUS              0x0004
#define DM9162_BMSR_JABBER_DETECT            0x0002
#define DM9162_BMSR_EXTENDED_CAPABLE         0x0001

//PHY Identifier 1 register
#define DM9162_PHYID1_OUI_MSB                0xFFFF
#define DM9162_PHYID1_OUI_MSB_DEFAULT        0x0181

//PHY Identifier 2 register
#define DM9162_PHYID2_OUI_LSB                0xFC00
#define DM9162_PHYID2_OUI_LSB_DEFAULT        0xB800
#define DM9162_PHYID2_VNDR_MDL               0x03F0
#define DM9162_PHYID2_VNDR_MDL_DEFAULT       0x0080
#define DM9162_PHYID2_MDL_REV                0x000F

//Auto-Negotiation Advertisement register
#define DM9162_ANAR_NEXT_PAGE                0x8000
#define DM9162_ANAR_ACK                      0x4000
#define DM9162_ANAR_REMOTE_FAULT             0x2000
#define DM9162_ANAR_FCS                      0x0400
#define DM9162_ANAR_100BT4                   0x0200
#define DM9162_ANAR_100BTX_FD                0x0100
#define DM9162_ANAR_100BTX_HD                0x0080
#define DM9162_ANAR_10BT_FD                  0x0040
#define DM9162_ANAR_10BT_HD                  0x0020
#define DM9162_ANAR_SELECTOR                 0x001F
#define DM9162_ANAR_SELECTOR_DEFAULT         0x0001

//Auto-Negotiation Link Partner Ability register
#define DM9162_ANLPAR_NEXT_PAGE              0x8000
#define DM9162_ANLPAR_ACK                    0x4000
#define DM9162_ANLPAR_REMOTE_FAULT           0x2000
#define DM9162_ANLPAR_FCS                    0x0400
#define DM9162_ANLPAR_100BT4                 0x0200
#define DM9162_ANLPAR_100BTX_FD              0x0100
#define DM9162_ANLPAR_100BTX_HD              0x0080
#define DM9162_ANLPAR_10BT_FD                0x0040
#define DM9162_ANLPAR_10BT_HD                0x0020
#define DM9162_ANLPAR_SELECTOR               0x001F
#define DM9162_ANLPAR_SELECTOR_DEFAULT       0x0001

//Auto-Negotiation Expansion register
#define DM9162_ANER_PAR_DETECT_FAULT         0x0010
#define DM9162_ANER_LP_NP_ABLE               0x0008
#define DM9162_ANER_NP_ABLE                  0x0004
#define DM9162_ANER_PAGE_RX                  0x0002
#define DM9162_ANER_LP_AN_ABLE               0x0001

//DAVICOM Specified Configuration register
#define DM9162_DSCR_BP_4B5B                  0x8000
#define DM9162_DSCR_BP_SCR                   0x4000
#define DM9162_DSCR_BP_ALIGN                 0x2000
#define DM9162_DSCR_BP_ADPOK                 0x1000
#define DM9162_DSCR_REPEATER                 0x0800
#define DM9162_DSCR_TX                       0x0400
#define DM9162_DSCR_FEF                      0x0200
#define DM9162_DSCR_RMII_EN                  0x0100
#define DM9162_DSCR_F_LINK_100               0x0080
#define DM9162_DSCR_SPLED_CTL                0x0040
#define DM9162_DSCR_COLLED_CTL               0x0020
#define DM9162_DSCR_RPDCTR_EN                0x0010
#define DM9162_DSCR_SMRST                    0x0008
#define DM9162_DSCR_MFPSC                    0x0004
#define DM9162_DSCR_SLEEP                    0x0002
#define DM9162_DSCR_RLOUT                    0x0001

//DAVICOM Specified Configuration and Status register
#define DM9162_DSCSR_100FDX                  0x8000
#define DM9162_DSCSR_100HDX                  0x4000
#define DM9162_DSCSR_10FDX                   0x2000
#define DM9162_DSCSR_10HDX                   0x1000
#define DM9162_DSCSR_PHYADR                  0x01F0
#define DM9162_DSCSR_ANMB                    0x000F
#define DM9162_DSCSR_ANMB_IDLE               0x0000
#define DM9162_DSCSR_ANMB_ABILITY_MATCH      0x0001
#define DM9162_DSCSR_ANMB_ACK_MATCH          0x0002
#define DM9162_DSCSR_ANMB_ACK_MATCH_FAIL     0x0003
#define DM9162_DSCSR_ANMB_CONSIST_MATCH      0x0004
#define DM9162_DSCSR_ANMB_CONSIST_MATCH_FAIL 0x0005
#define DM9162_DSCSR_ANMB_LINK_READY         0x0006
#define DM9162_DSCSR_ANMB_LINK_READY_FAIL    0x0007
#define DM9162_DSCSR_ANMB_AN_COMPLETE        0x0008

//10BASE-T Configuration/Status register
#define DM9162_10BTCSR_LP_EN                 0x4000
#define DM9162_10BTCSR_HBE                   0x2000
#define DM9162_10BTCSR_SQUELCH               0x1000
#define DM9162_10BTCSR_JABEN                 0x0800
#define DM9162_10BTCSR_10BT_SER              0x0400
#define DM9162_10BTCSR_POLR                  0x0001

//DAVICOM Specified Interrupt register
#define DM9162_MDINTR_INTR_PEND              0x8000
#define DM9162_MDINTR_FDX_MASK               0x0800
#define DM9162_MDINTR_SPD_MASK               0x0400
#define DM9162_MDINTR_LINK_MASK              0x0200
#define DM9162_MDINTR_INTR_MASK              0x0100
#define DM9162_MDINTR_FDX_CHANGE             0x0010
#define DM9162_MDINTR_SPD_CHANGE             0x0008
#define DM9162_MDINTR_LINK_CHANGE            0x0004
#define DM9162_MDINTR_INTR_STATUS            0x0001

//DAVICOM Specified Disconnect Counter register
#define DM9162_DISCR_DISCONNECT_COUNT        0x00FF

//DAVICOM Hardware Reset Latch State register
#define DM9162_RLSR_LH_LEDST                 0x2000
#define DM9162_RLSR_LH_CSTS                  0x1000
#define DM9162_RLSR_LH_RMII                  0x0800
#define DM9162_RLSR_LH_SCRAM                 0x0400
#define DM9162_RLSR_LH_REPTR                 0x0200
#define DM9162_RLSR_LH_TSTMOD                0x0100
#define DM9162_RLSR_LH_OP                    0x00E0
#define DM9162_RLSR_LH_PH                    0x001F

//C++ guard
#ifdef __cplusplus
extern "C" {
#endif

//DM9162 Ethernet PHY driver
extern const PhyDriver dm9162PhyDriver;

//DM9162 related functions
error_t dm9162Init(NetInterface *interface);

void dm9162Tick(NetInterface *interface);

void dm9162EnableIrq(NetInterface *interface);
void dm9162DisableIrq(NetInterface *interface);

void dm9162EventHandler(NetInterface *interface);

void dm9162WritePhyReg(NetInterface *interface, uint8_t address,
   uint16_t data);

uint16_t dm9162ReadPhyReg(NetInterface *interface, uint8_t address);

void dm9162DumpPhyReg(NetInterface *interface);

//C++ guard
#ifdef __cplusplus
}
#endif

#endif



main.c源代码

/**
* @file main.c
* @brief Main routine
*
* @section License
*
* Copyright (C) 2010-2022 Oryx Embedded SARL. All rights reserved.
*
* This file is part of CycloneTCP Eval.
*
* This software is provided in source form for a short-term evaluation only. The
* evaluation license expires 90 days after the date you first download the software.
*
* If you plan to use this software in a commercial product, you are required to
* purchase a commercial license from Oryx Embedded SARL.
*
* After the 90-day evaluation period, you agree to either purchase a commercial
* license or delete all copies of this software. If you wish to extend the
* evaluation period, you must contact sales@oryx-embedded.com.
*
* This evaluation software is provided "as is" without warranty of any kind.
* Technical support is available as an option during the evaluation period.
*
* @author Oryx Embedded SARL (www.oryx-embedded.com)
* @version 2.1.8
**/

//Dependencies
#include <stdlib.h>
#include "at32f435_437_board.h"
#include "at32f435_437_clock.h"
#include "core/net.h"
#include "drivers/mac/at32f437_eth_driver.h"
#include "drivers/phy/dm9162_driver.h"
#include "dhcp/dhcp_client.h"
#include "ipv6/slaac.h"
#include "ftp/ftp_client.h"
#include "debug.h"

//Ethernet interface configuration
#define APP_IF_NAME "eth0"
#define APP_HOST_NAME "ftp-client-demo"
#define APP_MAC_ADDR "00-AB-CD-EF-04-37"

#define APP_USE_DHCP_CLIENT DISABLED
#define APP_IPV4_HOST_ADDR "192.168.1.90"
#define APP_IPV4_SUBNET_MASK "255.255.255.0"
#define APP_IPV4_DEFAULT_GATEWAY "192.168.1.1"
#define APP_IPV4_PRIMARY_DNS "8.8.8.8"
#define APP_IPV4_SECONDARY_DNS "8.8.4.4"

#define APP_USE_SLAAC DISABLED
#define APP_IPV6_LINK_LOCAL_ADDR "fe80::307"
#define APP_IPV6_PREFIX "2001:db8::"
#define APP_IPV6_PREFIX_LENGTH 64
#define APP_IPV6_GLOBAL_ADDR "2001:db8::307"
#define APP_IPV6_ROUTER "fe80::1"
#define APP_IPV6_PRIMARY_DNS "2001:4860:4860::8888"
#define APP_IPV6_SECONDARY_DNS "2001:4860:4860::8844"

//Application configuration
#define APP_FTP_SERVER_NAME "test.rebex.net"
#define APP_FTP_SERVER_PORT 21
#define APP_FTP_LOGIN "demo"
#define APP_FTP_PASSWORD "password"
#define APP_FTP_FILENAME "readme.txt"

//Global variables
DhcpClientSettings dhcpClientSettings;
DhcpClientContext dhcpClientContext;
SlaacSettings slaacSettings;
SlaacContext slaacContext;
FtpClientContext ftpClientContext;


/**
* @brief FTP client test routine
* @return Error code
**/

error_t ftpClientTest(void)
{
   error_t error;
   size_t n;
   IpAddr ipAddr;
   char_t buffer[128];

   //Initialize FTP client context
   ftpClientInit(&ftpClientContext);

   //Start of exception handling block
   do
   {
      //Debug message
      TRACE_INFO("\r\n\r\nResolving server name...\r\n");

      //Resolve FTP server name
      error = getHostByName(NULL, APP_FTP_SERVER_NAME, &ipAddr, 0);
      //Any error to report?
      if(error)
      {
         //Debug message
         TRACE_INFO("Failed to resolve server name!\r\n");
         break;
      }

      //Set timeout value for blocking operations
      error = ftpClientSetTimeout(&ftpClientContext, 20000);
      //Any error to report?
      if(error)
         break;

      //Debug message
      TRACE_INFO("Connecting to FTP server %s...\r\n",
         ipAddrToString(&ipAddr, NULL));

      //Connect to the FTP server
      error = ftpClientConnect(&ftpClientContext, &ipAddr, APP_FTP_SERVER_PORT,
         FTP_MODE_PLAINTEXT | FTP_MODE_PASSIVE);
      //Any error to report?
      if(error)
      {
         //Debug message
         TRACE_INFO("Failed to connect to FTP server!\r\n");
         break;
      }

      //Login to the FTP server using the provided username and password
      error = ftpClientLogin(&ftpClientContext, APP_FTP_LOGIN, APP_FTP_PASSWORD);
      //Any error to report?
      if(error)
         break;

      //Open the specified file for reading
      error = ftpClientOpenFile(&ftpClientContext, APP_FTP_FILENAME,
         FTP_FILE_MODE_READ | FTP_FILE_MODE_BINARY);
      //Any error to report?
      if(error)
         break;

      //Read the contents of the file
      while(!error)
      {
         //Read data
         error = ftpClientReadFile(&ftpClientContext, buffer, sizeof(buffer) - 1, &n, 0);

         //Check status code
         if(!error)
         {
            //Properly terminate the string with a NULL character
            buffer[n] = '\0';
            //Dump the contents of the file
            TRACE_INFO("%s", buffer);
         }
      }

      //Terminate the string with a line feed
      TRACE_INFO("\r\n");

      //Any error to report?
      if(error != ERROR_END_OF_STREAM)
         break;

      //Close file
      error = ftpClientCloseFile(&ftpClientContext);
      //Any error to report?
      if(error)
         break;

      //Gracefully disconnect from the FTP server
      ftpClientDisconnect(&ftpClientContext);

      //Debug message
      TRACE_INFO("Connection closed\r\n");

      //End of exception handling block
   } while(0);

   //Release FTP client context
   ftpClientDeinit(&ftpClientContext);

   //Return status code
   return error;
}


/**
* @brief User task
* @param[in] param Unused parameter
**/

void userTask(void *param)
{
   //Endless loop
   while(1)
   {
      //User button pressed?
      if(at32_button_press() == USER_BUTTON)
      {
         //FTP client test routine
         ftpClientTest();
      }

      //Loop delay
      osDelayTask(100);
   }
}


/**
* @brief LED task
* @param[in] param Unused parameter
**/

void ledTask(void *param)
{
        //Endless loop
        while(1)
        {
                at32_led_on(LED2);
                osDelayTask(100);
                at32_led_off(LED2);
                osDelayTask(900);
        }
}


/**
* @brief Main entry point
* @return Unused value
**/

int_t main(void)
{
        error_t error;
        OsTaskId taskId;
        NetInterface *interface;
        MacAddr macAddr;
#if (APP_USE_DHCP_CLIENT == DISABLED)
        Ipv4Addr ipv4Addr;
#endif
#if (APP_USE_SLAAC == DISABLED)
        Ipv6Addr ipv6Addr;
#endif

        //system clock config
        system_clock_config();       
        nvic_priority_group_config(NVIC_PRIORITY_GROUP_4);
        //Initialize kernel
        osInitKernel();
        //Configure debug UART
        debugInit(115200);

        //Start-up message
        TRACE_INFO("\r\n");
        TRACE_INFO("**********************************\r\n");
        TRACE_INFO("*** CycloneTCP FTP Client Demo ***\r\n");
        TRACE_INFO("**********************************\r\n");
        TRACE_INFO("Copyright: 2010-2022 Oryx Embedded SARL\r\n");
        TRACE_INFO("Compiled: %s %s\r\n", __DATE__, __TIME__);
        TRACE_INFO("Target: AT32F437\r\n");
        TRACE_INFO("\r\n");

        //at32f437 board configuration
        at32_board_init();

        //TCP/IP stack initialization
        error = netInit();
        //Any error to report?
        if(error)
        {
                //Debug message
                TRACE_ERROR("Failed to initialize TCP/IP stack!\r\n");
        }

        //Configure the first Ethernet interface
        interface = &netInterface[0];

        //Set interface name
        netSetInterfaceName(interface, APP_IF_NAME);
        //Set host name
        netSetHostname(interface, APP_HOST_NAME);
        //Set host MAC address
        macStringToAddr(APP_MAC_ADDR, &macAddr);
        netSetMacAddr(interface, &macAddr);
        //Select the relevant network adapter
        netSetDriver(interface, &at32f437EthDriver);
        netSetPhyDriver(interface, &dm9162PhyDriver);

        //Initialize network interface
        error = netConfigInterface(interface);
        //Any error to report?
        if(error)
        {
                //Debug message
                TRACE_ERROR("Failed to configure interface %s!\r\n", interface->name);
        }

#if (IPV4_SUPPORT == ENABLED)
#if (APP_USE_DHCP_CLIENT == ENABLED)
        //Get default settings
        dhcpClientGetDefaultSettings(&dhcpClientSettings);
        //Set the network interface to be configured by DHCP
        dhcpClientSettings.interface = interface;
        //Disable rapid commit option
        dhcpClientSettings.rapidCommit = FALSE;

        //DHCP client initialization
        error = dhcpClientInit(&dhcpClientContext, &dhcpClientSettings);
        //Failed to initialize DHCP client?
        if(error)
        {
                //Debug message
                TRACE_ERROR("Failed to initialize DHCP client!\r\n");
        }

        //Start DHCP client
        error = dhcpClientStart(&dhcpClientContext);
        //Failed to start DHCP client?
        if(error)
        {
                //Debug message
                TRACE_ERROR("Failed to start DHCP client!\r\n");
        }
#else
        //Set IPv4 host address
        ipv4StringToAddr(APP_IPV4_HOST_ADDR, &ipv4Addr);
        ipv4SetHostAddr(interface, ipv4Addr);

        //Set subnet mask
        ipv4StringToAddr(APP_IPV4_SUBNET_MASK, &ipv4Addr);
        ipv4SetSubnetMask(interface, ipv4Addr);

        //Set default gateway
        ipv4StringToAddr(APP_IPV4_DEFAULT_GATEWAY, &ipv4Addr);
        ipv4SetDefaultGateway(interface, ipv4Addr);

        //Set primary and secondary DNS servers
        ipv4StringToAddr(APP_IPV4_PRIMARY_DNS, &ipv4Addr);
        ipv4SetDnsServer(interface, 0, ipv4Addr);
        ipv4StringToAddr(APP_IPV4_SECONDARY_DNS, &ipv4Addr);
        ipv4SetDnsServer(interface, 1, ipv4Addr);
#endif
#endif

#if (IPV6_SUPPORT == ENABLED)
#if (APP_USE_SLAAC == ENABLED)
        //Get default settings
        slaacGetDefaultSettings(&slaacSettings);
        //Set the network interface to be configured
        slaacSettings.interface = interface;

        //SLAAC initialization
        error = slaacInit(&slaacContext, &slaacSettings);
        //Failed to initialize SLAAC?
        if(error)
        {
                //Debug message
                TRACE_ERROR("Failed to initialize SLAAC!\r\n");
        }

        //Start IPv6 address autoconfiguration process
        error = slaacStart(&slaacContext);
        //Failed to start SLAAC process?
        if(error)
        {
                //Debug message
                TRACE_ERROR("Failed to start SLAAC!\r\n");
        }
#else
        //Set link-local address
        ipv6StringToAddr(APP_IPV6_LINK_LOCAL_ADDR, &ipv6Addr);
        ipv6SetLinkLocalAddr(interface, &ipv6Addr);

        //Set IPv6 prefix
        ipv6StringToAddr(APP_IPV6_PREFIX, &ipv6Addr);
        ipv6SetPrefix(interface, 0, &ipv6Addr, APP_IPV6_PREFIX_LENGTH);

        //Set global address
        ipv6StringToAddr(APP_IPV6_GLOBAL_ADDR, &ipv6Addr);
        ipv6SetGlobalAddr(interface, 0, &ipv6Addr);

        //Set default router
        ipv6StringToAddr(APP_IPV6_ROUTER, &ipv6Addr);
        ipv6SetDefaultRouter(interface, 0, &ipv6Addr);

        //Set primary and secondary DNS servers
        ipv6StringToAddr(APP_IPV6_PRIMARY_DNS, &ipv6Addr);
        ipv6SetDnsServer(interface, 0, &ipv6Addr);
        ipv6StringToAddr(APP_IPV6_SECONDARY_DNS, &ipv6Addr);
        ipv6SetDnsServer(interface, 1, &ipv6Addr);
#endif
#endif

        //Create user task
        taskId = osCreateTask("User", userTask, NULL, 1024, OS_TASK_PRIORITY_NORMAL);
        //Failed to create the task?
        if(taskId == OS_INVALID_TASK_ID)
        {
                //Debug message
                TRACE_ERROR("Failed to create task!\r\n");
        }

        //Create a task to blink the LED
        taskId = osCreateTask("LED", ledTask, NULL, 1024, OS_TASK_PRIORITY_NORMAL);
        //Failed to create the task?
        if(taskId == OS_INVALID_TASK_ID)
        {
                //Debug message
                TRACE_ERROR("Failed to create task!\r\n");
        }

        //Start the execution of tasks
        osStartKernel();

        //This function should never return
        return 0;
}




3.png (375.4 KB )

接收中断无法正常进入

接收中断无法正常进入

2.png (178.98 KB )

发出IGMPv2协议报文

发出IGMPv2协议报文

1.png (35.9 KB )

识别10MHz

识别10MHz

使用特权

评论回复
沙发
muyichuan2012| | 2023-1-3 10:51 | 只看该作者
建议参考附件FAQ排查

FAQ0139_AT32F407_437网口初始化卡在EMAC DMA软件复位_V2.0.0.pdf

122.71 KB

使用特权

评论回复
板凳
乱世流年|  楼主 | 2023-1-3 11:10 | 只看该作者
muyichuan2012 发表于 2023-1-3 10:51
建议参考附件FAQ排查

感谢,官网的这些文档我已经阅读过了,目前不是初始化卡住,而是初始化自识别的模式和数据收发好像不太对,就是没有特定的讲解EMAC外设的流程文档,就不太清楚到底问题出在哪里,是设置不对还是时序有问题

使用特权

评论回复
地板
乱世流年|  楼主 | 2023-1-3 13:12 | 只看该作者
有没有雅特力的FAE联系方式,在官网填写了相关问题描述,没有反应

使用特权

评论回复
评论
muyichuan2012 2023-1-3 19:38 回复TA
FAE已经与您取得联系。 
5
caigang13| | 2023-1-3 21:01 | 只看该作者
我去,一来就是一长段代码,成功逼走了看问题的人。

使用特权

评论回复
6
乱世流年|  楼主 | 2023-1-6 13:23 | 只看该作者
网络驱动问题已经解决,具体情况可移步至新帖子查看 https://bbs.21ic.com/icview-3276754-1-1.html

使用特权

评论回复
7
Bowclad| | 2023-2-7 19:06 | 只看该作者
代码这么长

使用特权

评论回复
8
mnynt121| | 2023-3-2 10:23 | 只看该作者
这个可以,是官网的代码吗?              

使用特权

评论回复
9
10299823| | 2023-3-2 10:53 | 只看该作者
之前都是使用 的wifi进行通信的。

使用特权

评论回复
10
robincotton| | 2023-3-2 11:20 | 只看该作者
CycloneTCP网络协议是谁开发 ?

使用特权

评论回复
11
ccook11| | 2023-3-2 16:38 | 只看该作者
这个是开源的通信协议的吗?              

使用特权

评论回复
12
wwppd| | 2023-3-2 16:55 | 只看该作者
期待楼主的移植的教程了。              

使用特权

评论回复
13
janewood| | 2023-3-3 21:35 | 只看该作者
这个可以实现mqtt通信的吗?              

使用特权

评论回复
14
houjiakai| | 2023-3-3 21:41 | 只看该作者
这个最大的通信速度可以多少的              

使用特权

评论回复
15
OKAKAKO| | 2023-3-7 17:07 | 只看该作者
这反映问题的太给力了,代码太长了

使用特权

评论回复
发新帖 我要提问
您需要登录后才可以回帖 登录 | 注册

本版积分规则

16

主题

308

帖子

2

粉丝