summaryrefslogtreecommitdiff
path: root/FreeRTOS-Plus/Source/FreeRTOS-Plus-TCP/portable/NetworkInterface/M487
diff options
context:
space:
mode:
Diffstat (limited to 'FreeRTOS-Plus/Source/FreeRTOS-Plus-TCP/portable/NetworkInterface/M487')
-rw-r--r--FreeRTOS-Plus/Source/FreeRTOS-Plus-TCP/portable/NetworkInterface/M487/NetworkInterface.c331
-rw-r--r--FreeRTOS-Plus/Source/FreeRTOS-Plus-TCP/portable/NetworkInterface/M487/m480_eth.c448
-rw-r--r--FreeRTOS-Plus/Source/FreeRTOS-Plus-TCP/portable/NetworkInterface/M487/m480_eth.h164
3 files changed, 943 insertions, 0 deletions
diff --git a/FreeRTOS-Plus/Source/FreeRTOS-Plus-TCP/portable/NetworkInterface/M487/NetworkInterface.c b/FreeRTOS-Plus/Source/FreeRTOS-Plus-TCP/portable/NetworkInterface/M487/NetworkInterface.c
new file mode 100644
index 000000000..e759141cc
--- /dev/null
+++ b/FreeRTOS-Plus/Source/FreeRTOS-Plus-TCP/portable/NetworkInterface/M487/NetworkInterface.c
@@ -0,0 +1,331 @@
+/*
+FreeRTOS+TCP V2.0.11
+Copyright (C) 2018 Amazon.com, Inc. or its affiliates. All Rights Reserved.
+
+Permission is hereby granted, free of charge, to any person obtaining a copy of
+this software and associated documentation files (the "Software"), to deal in
+the Software without restriction, including without limitation the rights to
+use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of
+the Software, and to permit persons to whom the Software is furnished to do so,
+subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
+FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR
+COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER
+IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN
+CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
+
+ http://aws.amazon.com/freertos
+ http://www.FreeRTOS.org
+*/
+
+/* FreeRTOS includes. */
+#include "FreeRTOS.h"
+#include "list.h"
+#include "queue.h"
+#include "semphr.h"
+#include "task.h"
+
+/* FreeRTOS+TCP includes. */
+#include "FreeRTOS_IP.h"
+#include "FreeRTOS_Sockets.h"
+#include "FreeRTOS_IP_Private.h"
+#include "NetworkBufferManagement.h"
+#include "NetworkInterface.h"
+
+
+#include "m480_eth.h"
+
+/* If ipconfigETHERNET_DRIVER_FILTERS_FRAME_TYPES is set to 1, then the Ethernet
+driver will filter incoming packets and only pass the stack those packets it
+considers need processing. */
+#if( ipconfigETHERNET_DRIVER_FILTERS_FRAME_TYPES == 0 )
+#define ipCONSIDER_FRAME_FOR_PROCESSING( pucEthernetBuffer ) eProcessBuffer
+#else
+#define ipCONSIDER_FRAME_FOR_PROCESSING( pucEthernetBuffer ) eConsiderFrameForProcessing( ( pucEthernetBuffer ) )
+#endif
+
+/* Default the size of the stack used by the EMAC deferred handler task to twice
+the size of the stack used by the idle task - but allow this to be overridden in
+FreeRTOSConfig.h as configMINIMAL_STACK_SIZE is a user definable constant. */
+#ifndef configEMAC_TASK_STACK_SIZE
+ #define configEMAC_TASK_STACK_SIZE ( 2 * configMINIMAL_STACK_SIZE )
+#endif
+
+
+static SemaphoreHandle_t xTXMutex = NULL;
+
+/* The handle of the task that processes Rx packets. The handle is required so
+the task can be notified when new packets arrive. */
+static TaskHandle_t xRxHanderTask = NULL;
+static TimerHandle_t xPhyHandlerTask = NULL;
+/*
+ * A task that processes received frames.
+ */
+static void prvEMACHandlerTask( void *pvParameters );
+static void prvPhyTmrCallback( TimerHandle_t xTimer );
+
+/* The size of each buffer when BufferAllocation_1 is used:
+http://www.freertos.org/FreeRTOS-Plus/FreeRTOS_Plus_TCP/Embedded_Ethernet_Buffer_Management.html */
+
+#define niBUFFER_1_PACKET_SIZE 1536
+#ifdef __ICCARM__
+#pragma data_alignment=4
+static uint8_t ucNetworkPackets[ ipconfigNUM_NETWORK_BUFFER_DESCRIPTORS * niBUFFER_1_PACKET_SIZE ]
+#else
+static uint8_t ucNetworkPackets[ ipconfigNUM_NETWORK_BUFFER_DESCRIPTORS * niBUFFER_1_PACKET_SIZE ] __attribute__ ((aligned(4)));
+#endif
+
+BaseType_t xNetworkInterfaceInitialise( void )
+{
+ uint8_t hwaddr[6];
+ BaseType_t xReturn = pdPASS;
+
+ /* Init ETH */
+ numaker_mac_address(hwaddr);
+ FreeRTOS_UpdateMACAddress(hwaddr);
+ FreeRTOS_printf( ("mac address %02x-%02x-%02x-%02x-%02x-%02x \r\n", hwaddr[0], hwaddr[1],hwaddr[2],hwaddr[3],hwaddr[4],hwaddr[5]) );
+ /* Enable clock & set EMAC configuration */
+ /* Enable MAC and DMA transmission and reception */
+ if( numaker_eth_init(hwaddr) < 0)
+ {
+ xReturn = pdFAIL;
+ } else {
+ xReturn = pdPASS;
+ /* Guard against the task being created more than once and the
+ descriptors being initialized more than once. */
+ /* Timer task to monitor PHY Link status */
+ if( xPhyHandlerTask == NULL )
+ {
+ xPhyHandlerTask = xTimerCreate( "TimerPhy", pdMS_TO_TICKS( 1000 ), pdTRUE, 0, prvPhyTmrCallback );
+ configASSERT(xPhyHandlerTask);
+ xReturn = xTimerStart( xPhyHandlerTask, 0 ) ;
+ configASSERT( xReturn );
+ }
+ /* Rx task */
+ if( xRxHanderTask == NULL )
+ {
+ xReturn = xTaskCreate( prvEMACHandlerTask, "EMAC", configEMAC_TASK_STACK_SIZE, NULL, configMAX_PRIORITIES - 1, &xRxHanderTask );
+ configASSERT( xReturn );
+ }
+
+ if( xTXMutex == NULL )
+ {
+ xTXMutex = xSemaphoreCreateMutex();
+ configASSERT( xTXMutex );
+ }
+ }
+
+ NVIC_SetPriority( EMAC_RX_IRQn, configMAC_INTERRUPT_PRIORITY );
+ NVIC_SetPriority( EMAC_TX_IRQn, configMAC_INTERRUPT_PRIORITY );
+
+ numaker_eth_enable_interrupts();
+
+ FreeRTOS_printf( ("ETH-RX priority:%d\n",NVIC_GetPriority( EMAC_RX_IRQn)) );
+
+ return xReturn;
+}
+
+BaseType_t xNetworkInterfaceOutput( NetworkBufferDescriptor_t * const pxDescriptor, BaseType_t xReleaseAfterSend )
+{
+ uint8_t *buffer=NULL;
+// FreeRTOS_printf(("<-- dataLength=%d\n",pxDescriptor->xDataLength));
+ if( pxDescriptor->xDataLength >= PACKET_BUFFER_SIZE )
+ {
+ FreeRTOS_printf(("TX buffer length %d over %d\n", pxDescriptor->xDataLength, PACKET_BUFFER_SIZE));
+ return pdFALSE;
+ }
+
+ buffer = numaker_eth_get_tx_buf();
+ if( buffer == NULL )
+ {
+ NU_DEBUGF(("Eth TX slots are busy\n"));
+ return pdFALSE;
+ }
+
+ /* Get exclusive access */
+ xSemaphoreTake(xTXMutex, portMAX_DELAY);
+ NU_DEBUGF(("%s ... buffer=0x%x\r\n",__FUNCTION__, buffer));
+ //SendData: pt = pxDescriptor->pucBuffer, length = pxDescriptor->xDataLength
+ memcpy(buffer, pxDescriptor->pucEthernetBuffer, pxDescriptor->xDataLength);
+ numaker_eth_trigger_tx(pxDescriptor->xDataLength, NULL);
+ /* Call the standard trace macro to log the send event. */
+ iptraceNETWORK_INTERFACE_TRANSMIT();
+
+ if( xReleaseAfterSend != pdFALSE )
+ {
+ /* It is assumed SendData() copies the data out of the FreeRTOS+TCP Ethernet
+ buffer. The Ethernet buffer is therefore no longer needed, and must be
+ freed for re-use. */
+ vReleaseNetworkBufferAndDescriptor( pxDescriptor );
+ }
+
+ xSemaphoreGive(xTXMutex);
+
+ return pdTRUE;
+}
+
+
+void vNetworkInterfaceAllocateRAMToBuffers( NetworkBufferDescriptor_t pxNetworkBuffers[ ipconfigNUM_NETWORK_BUFFER_DESCRIPTORS ] )
+{
+
+ uint8_t *ucRAMBuffer = ucNetworkPackets;
+ uint32_t ul;
+
+ for( ul = 0; ul < ipconfigNUM_NETWORK_BUFFER_DESCRIPTORS; ul++ )
+ {
+ pxNetworkBuffers[ ul ].pucEthernetBuffer = ucRAMBuffer + ipBUFFER_PADDING;
+ *( ( unsigned * ) ucRAMBuffer ) = ( unsigned ) ( &( pxNetworkBuffers[ ul ] ) );
+ ucRAMBuffer += niBUFFER_1_PACKET_SIZE;
+ }
+}
+
+
+BaseType_t xGetPhyLinkStatus( void )
+{
+ BaseType_t xReturn;
+
+ if( numaker_eth_link_ok() )
+ {
+ xReturn = pdPASS;
+ }
+ else
+ {
+ xReturn = pdFAIL;
+ }
+
+ return xReturn;
+}
+
+static void prvPhyTmrCallback( TimerHandle_t xTimer )
+{
+ IPStackEvent_t xRxEvent;
+ static BaseType_t lastLink = pdFAIL;
+ BaseType_t currLink = xGetPhyLinkStatus();
+ if( currLink != lastLink )
+ {
+ FreeRTOS_printf(("PHY Link %s\n", (currLink) ? "Up" : "Down"));
+ if( !currLink )
+ {
+ xRxEvent.eEventType = eNetworkDownEvent;
+ xSendEventStructToIPTask( &xRxEvent, 0 );
+ }
+ lastLink = currLink;
+ }
+
+}
+
+
+static void prvEMACHandlerTask( void *pvParameters )
+{
+ TimeOut_t xPhyTime;
+ TickType_t xPhyRemTime;
+ UBaseType_t uxLastMinBufferCount = 0;
+ UBaseType_t uxCurrentCount;
+ BaseType_t xResult = 0;
+ uint32_t ulStatus;
+ uint16_t dataLength = 0;
+ uint8_t *buffer = NULL;
+ NetworkBufferDescriptor_t *pxBufferDescriptor = NULL;
+ IPStackEvent_t xRxEvent;
+ const TickType_t xBlockTime = pdMS_TO_TICKS( 5000ul );
+
+ /* Remove compiler warnings about unused parameters. */
+ ( void ) pvParameters;
+ /* A possibility to set some additional task properties. */
+
+ for( ;; )
+ {
+ uxCurrentCount = uxGetMinimumFreeNetworkBuffers();
+ if( uxLastMinBufferCount != uxCurrentCount )
+ {
+ /* The logging produced below may be helpful
+ while tuning +TCP: see how many buffers are in use. */
+ uxLastMinBufferCount = uxCurrentCount;
+ FreeRTOS_printf( ( "Network buffers: %lu lowest %lu\n",
+ uxGetNumberOfFreeNetworkBuffers(), uxCurrentCount ) );
+ }
+
+ /* No events to process now, wait for the next. */
+ ulTaskNotifyTake( pdFALSE, portMAX_DELAY );
+ while(1)
+ {
+ /* get received frame */
+ if ( numaker_eth_get_rx_buf(&dataLength, &buffer) != 0) {
+ /* The event was lost because a network buffer was not available.
+ Call the standard trace macro to log the occurrence. */
+ iptraceETHERNET_RX_EVENT_LOST();
+ break;
+ }
+
+ /* Allocate a network buffer descriptor that points to a buffer
+ large enough to hold the received frame. As this is the simple
+ rather than efficient example the received data will just be copied
+ into this buffer. */
+
+ pxBufferDescriptor = pxGetNetworkBufferWithDescriptor( PACKET_BUFFER_SIZE, 0 );
+
+ if( pxBufferDescriptor != NULL )
+ {
+ memcpy( pxBufferDescriptor->pucEthernetBuffer, buffer, dataLength );
+// FreeRTOS_printf(("--> dataLength=%d\n",dataLength));
+ pxBufferDescriptor->xDataLength = dataLength;
+ } else {
+ numaker_eth_rx_next();
+ iptraceETHERNET_RX_EVENT_LOST();
+ break;
+ }
+ /* The event about to be sent to the TCP/IP is an Rx event. */
+ xRxEvent.eEventType = eNetworkRxEvent;
+
+ /* pvData is used to point to the network buffer descriptor that
+ now references the received data. */
+ xRxEvent.pvData = ( void * ) pxBufferDescriptor;
+
+ /* Send the data to the TCP/IP stack. */
+ if( xSendEventStructToIPTask( &xRxEvent, 0 ) == pdFALSE )
+ {
+ /* The buffer could not be sent to the IP task so the buffer
+ must be released. */
+ vReleaseNetworkBufferAndDescriptor( pxBufferDescriptor );
+
+ /* Make a call to the standard trace macro to log the
+ occurrence. */
+
+ iptraceETHERNET_RX_EVENT_LOST();
+ } else
+ {
+ /* The message was successfully sent to the TCP/IP stack.
+ Call the standard trace macro to log the occurrence. */
+ iptraceNETWORK_INTERFACE_RECEIVE();
+ }
+ numaker_eth_rx_next();
+ }
+ numaker_eth_trigger_rx();
+ }
+}
+
+void xNetworkCallback(char event)
+{
+ BaseType_t xHigherPriorityTaskWoken = pdFALSE;
+ switch (event)
+ {
+ case 'R': //For RX event
+ /* Wakeup the prvEMACHandlerTask. */
+ if( xRxHanderTask != NULL )
+ {
+ vTaskNotifyGiveFromISR( xRxHanderTask, &xHigherPriorityTaskWoken );
+ portYIELD_FROM_ISR( xHigherPriorityTaskWoken );
+ }
+ break;
+ case 'T': //For TX event
+ // ack of tx done, no-op in this stage
+ break;
+ default:
+ break;
+ }
+}
diff --git a/FreeRTOS-Plus/Source/FreeRTOS-Plus-TCP/portable/NetworkInterface/M487/m480_eth.c b/FreeRTOS-Plus/Source/FreeRTOS-Plus-TCP/portable/NetworkInterface/M487/m480_eth.c
new file mode 100644
index 000000000..2d45661d0
--- /dev/null
+++ b/FreeRTOS-Plus/Source/FreeRTOS-Plus-TCP/portable/NetworkInterface/M487/m480_eth.c
@@ -0,0 +1,448 @@
+/**************************************************************************//**
+ * @copyright (C) 2019 Nuvoton Technology Corp. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of Nuvoton Technology Corp. nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*****************************************************************************/
+#include "FreeRTOS.h"
+#include "list.h"
+#include "FreeRTOS_IP.h"
+
+#include "m480_eth.h"
+
+#define ETH_TRIGGER_RX() do{EMAC->RXST = 0;}while(0)
+#define ETH_TRIGGER_TX() do{EMAC->TXST = 0;}while(0)
+#define ETH_ENABLE_TX() do{EMAC->CTL |= EMAC_CTL_TXON;}while(0)
+#define ETH_ENABLE_RX() do{EMAC->CTL |= EMAC_CTL_RXON;}while(0)
+#define ETH_DISABLE_TX() do{EMAC->CTL &= ~EMAC_CTL_TXON;}while(0)
+#define ETH_DISABLE_RX() do{EMAC->CTL &= ~EMAC_CTL_RXON;}while(0)
+
+
+struct eth_descriptor rx_desc[RX_DESCRIPTOR_NUM] __attribute__ ((aligned(4)));
+struct eth_descriptor tx_desc[TX_DESCRIPTOR_NUM] __attribute__ ((aligned(4)));
+#ifdef __ICCARM__
+#pragma data_alignment=4
+struct eth_descriptor rx_desc[RX_DESCRIPTOR_NUM];
+struct eth_descriptor tx_desc[TX_DESCRIPTOR_NUM];
+uint8_t rx_buf[RX_DESCRIPTOR_NUM][PACKET_BUFFER_SIZE];
+uint8_t tx_buf[TX_DESCRIPTOR_NUM][PACKET_BUFFER_SIZE];
+#else
+struct eth_descriptor rx_desc[RX_DESCRIPTOR_NUM] __attribute__ ((aligned(4)));
+struct eth_descriptor tx_desc[TX_DESCRIPTOR_NUM] __attribute__ ((aligned(4)));
+uint8_t rx_buf[RX_DESCRIPTOR_NUM][PACKET_BUFFER_SIZE] __attribute__ ((aligned(4)));
+uint8_t tx_buf[TX_DESCRIPTOR_NUM][PACKET_BUFFER_SIZE] __attribute__ ((aligned(4)));
+#endif
+struct eth_descriptor volatile *cur_tx_desc_ptr, *cur_rx_desc_ptr, *fin_tx_desc_ptr;
+
+
+// PTP source clock is 84MHz (Real chip using PLL). Each tick is 11.90ns
+// Assume we want to set each tick to 100ns.
+// Increase register = (100 * 2^31) / (10^9) = 214.71 =~ 215 = 0xD7
+// Addend register = 2^32 * tick_freq / (84MHz), where tick_freq = (2^31 / 215) MHz
+// From above equation, addend register = 2^63 / (84M * 215) ~= 510707200 = 0x1E70C600
+
+
+
+static void mdio_write(uint8_t addr, uint8_t reg, uint16_t val)
+{
+
+ EMAC->MIIMDAT = val;
+ EMAC->MIIMCTL = (addr << EMAC_MIIMCTL_PHYADDR_Pos) | reg | EMAC_MIIMCTL_BUSY_Msk | EMAC_MIIMCTL_WRITE_Msk | EMAC_MIIMCTL_MDCON_Msk;
+
+ while (EMAC->MIIMCTL & EMAC_MIIMCTL_BUSY_Msk);
+
+}
+
+
+static uint16_t mdio_read(uint8_t addr, uint8_t reg)
+{
+ EMAC->MIIMCTL = (addr << EMAC_MIIMCTL_PHYADDR_Pos) | reg | EMAC_MIIMCTL_BUSY_Msk | EMAC_MIIMCTL_MDCON_Msk;
+ while (EMAC->MIIMCTL & EMAC_MIIMCTL_BUSY_Msk);
+
+ return(EMAC->MIIMDAT);
+}
+
+static int reset_phy(void)
+{
+
+ uint16_t reg;
+ uint32_t delayCnt;
+
+
+ mdio_write(CONFIG_PHY_ADDR, MII_BMCR, BMCR_RESET);
+
+ delayCnt = 2000;
+ while(delayCnt-- > 0) {
+ if((mdio_read(CONFIG_PHY_ADDR, MII_BMCR) & BMCR_RESET) == 0)
+ break;
+
+ }
+
+ if(delayCnt == 0) {
+ NU_DEBUGF(("Reset phy failed\n"));
+ return(-1);
+ }
+
+ mdio_write(CONFIG_PHY_ADDR, MII_ADVERTISE, ADVERTISE_CSMA |
+ ADVERTISE_10HALF |
+ ADVERTISE_10FULL |
+ ADVERTISE_100HALF |
+ ADVERTISE_100FULL);
+
+ reg = mdio_read(CONFIG_PHY_ADDR, MII_BMCR);
+ mdio_write(CONFIG_PHY_ADDR, MII_BMCR, reg | BMCR_ANRESTART);
+
+ delayCnt = 200000;
+ while(delayCnt-- > 0) {
+ if((mdio_read(CONFIG_PHY_ADDR, MII_BMSR) & (BMSR_ANEGCOMPLETE | BMSR_LSTATUS))
+ == (BMSR_ANEGCOMPLETE | BMSR_LSTATUS))
+ break;
+ }
+
+ if(delayCnt == 0) {
+ NU_DEBUGF(("AN failed. Set to 100 FULL\n"));
+ EMAC->CTL |= (EMAC_CTL_OPMODE_Msk | EMAC_CTL_FUDUP_Msk);
+ return(-1);
+ } else {
+ reg = mdio_read(CONFIG_PHY_ADDR, MII_LPA);
+
+ if(reg & ADVERTISE_100FULL) {
+ NU_DEBUGF(("100 full\n"));
+ EMAC->CTL |= (EMAC_CTL_OPMODE_Msk | EMAC_CTL_FUDUP_Msk);
+ } else if(reg & ADVERTISE_100HALF) {
+ NU_DEBUGF(("100 half\n"));
+ EMAC->CTL = (EMAC->CTL & ~EMAC_CTL_FUDUP_Msk) | EMAC_CTL_OPMODE_Msk;
+ } else if(reg & ADVERTISE_10FULL) {
+ NU_DEBUGF(("10 full\n"));
+ EMAC->CTL = (EMAC->CTL & ~EMAC_CTL_OPMODE_Msk) | EMAC_CTL_FUDUP_Msk;
+ } else {
+ NU_DEBUGF(("10 half\n"));
+ EMAC->CTL &= ~(EMAC_CTL_OPMODE_Msk | EMAC_CTL_FUDUP_Msk);
+ }
+ }
+ FreeRTOS_printf(("PHY ID 1:0x%x\r\n", mdio_read(CONFIG_PHY_ADDR, MII_PHYSID1)));
+ FreeRTOS_printf(("PHY ID 2:0x%x\r\n", mdio_read(CONFIG_PHY_ADDR, MII_PHYSID2)));
+
+ return(0);
+}
+
+
+static void init_tx_desc(void)
+{
+ uint32_t i;
+
+
+ cur_tx_desc_ptr = fin_tx_desc_ptr = &tx_desc[0];
+
+ for(i = 0; i < TX_DESCRIPTOR_NUM; i++) {
+ tx_desc[i].status1 = TXFD_PADEN | TXFD_CRCAPP | TXFD_INTEN;
+ tx_desc[i].buf = &tx_buf[i][0];
+ tx_desc[i].status2 = 0;
+ tx_desc[i].next = &tx_desc[(i + 1) % TX_DESCRIPTOR_NUM];
+
+ }
+ EMAC->TXDSA = (unsigned int)&tx_desc[0];
+ return;
+}
+
+static void init_rx_desc(void)
+{
+ uint32_t i;
+
+
+ cur_rx_desc_ptr = &rx_desc[0];
+
+ for(i = 0; i < RX_DESCRIPTOR_NUM; i++) {
+ rx_desc[i].status1 = OWNERSHIP_EMAC;
+ rx_desc[i].buf = &rx_buf[i][0];
+ rx_desc[i].status2 = 0;
+ rx_desc[i].next = &rx_desc[(i + 1) % TX_DESCRIPTOR_NUM];
+ }
+ EMAC->RXDSA = (unsigned int)&rx_desc[0];
+ return;
+}
+
+void numaker_set_mac_addr(uint8_t *addr)
+{
+
+ EMAC->CAM0M = (addr[0] << 24) |
+ (addr[1] << 16) |
+ (addr[2] << 8) |
+ addr[3];
+
+ EMAC->CAM0L = (addr[4] << 24) |
+ (addr[5] << 16);
+
+
+}
+
+static void __eth_clk_pin_init()
+{
+ /* Unlock protected registers */
+ SYS_UnlockReg();
+
+ /* Enable IP clock */
+ CLK_EnableModuleClock(EMAC_MODULE);
+
+ // Configure MDC clock rate to HCLK / (127 + 1) = 1.25 MHz if system is running at 160 MH
+ CLK_SetModuleClock(EMAC_MODULE, 0, CLK_CLKDIV3_EMAC(127));
+
+ /* Update System Core Clock */
+ SystemCoreClockUpdate();
+
+ /*---------------------------------------------------------------------------------------------------------*/
+ /* Init I/O Multi-function */
+ /*---------------------------------------------------------------------------------------------------------*/
+ // Configure RMII pins
+ SYS->GPA_MFPL &= ~(SYS_GPA_MFPL_PA6MFP_Msk | SYS_GPA_MFPL_PA7MFP_Msk);
+ SYS->GPA_MFPL |= SYS_GPA_MFPL_PA6MFP_EMAC_RMII_RXERR | SYS_GPA_MFPL_PA7MFP_EMAC_RMII_CRSDV;
+ SYS->GPC_MFPL &= ~(SYS_GPC_MFPL_PC6MFP_Msk | SYS_GPC_MFPL_PC7MFP_Msk);
+ SYS->GPC_MFPL |= SYS_GPC_MFPL_PC6MFP_EMAC_RMII_RXD1 | SYS_GPC_MFPL_PC7MFP_EMAC_RMII_RXD0;
+ SYS->GPC_MFPH &= ~SYS_GPC_MFPH_PC8MFP_Msk;
+ SYS->GPC_MFPH |= SYS_GPC_MFPH_PC8MFP_EMAC_RMII_REFCLK;
+ SYS->GPE_MFPH &= ~(SYS_GPE_MFPH_PE8MFP_Msk | SYS_GPE_MFPH_PE9MFP_Msk | SYS_GPE_MFPH_PE10MFP_Msk |
+ SYS_GPE_MFPH_PE11MFP_Msk | SYS_GPE_MFPH_PE12MFP_Msk);
+ SYS->GPE_MFPH |= SYS_GPE_MFPH_PE8MFP_EMAC_RMII_MDC |
+ SYS_GPE_MFPH_PE9MFP_EMAC_RMII_MDIO |
+ SYS_GPE_MFPH_PE10MFP_EMAC_RMII_TXD0 |
+ SYS_GPE_MFPH_PE11MFP_EMAC_RMII_TXD1 |
+ SYS_GPE_MFPH_PE12MFP_EMAC_RMII_TXEN;
+
+ // Enable high slew rate on all RMII TX output pins
+ PE->SLEWCTL = (GPIO_SLEWCTL_HIGH << GPIO_SLEWCTL_HSREN10_Pos) |
+ (GPIO_SLEWCTL_HIGH << GPIO_SLEWCTL_HSREN11_Pos) |
+ (GPIO_SLEWCTL_HIGH << GPIO_SLEWCTL_HSREN12_Pos);
+
+
+ /* Lock protected registers */
+ SYS_LockReg();
+
+
+}
+
+int numaker_eth_init(uint8_t *mac_addr)
+{
+ int ret = 0;
+ // init CLK & pins
+ __eth_clk_pin_init();
+
+ // Reset MAC
+ EMAC->CTL = EMAC_CTL_RST_Msk;
+ while(EMAC->CTL & EMAC_CTL_RST_Msk) {}
+
+ init_tx_desc();
+ init_rx_desc();
+
+ numaker_set_mac_addr(mac_addr); // need to reconfigure hardware address 'cos we just RESET emc...
+
+
+ /* Configure the MAC interrupt enable register. */
+ EMAC->INTEN = EMAC_INTEN_RXIEN_Msk |
+ EMAC_INTEN_TXIEN_Msk |
+ EMAC_INTEN_RXGDIEN_Msk |
+ EMAC_INTEN_TXCPIEN_Msk |
+ EMAC_INTEN_RXBEIEN_Msk |
+ EMAC_INTEN_TXBEIEN_Msk |
+ EMAC_INTEN_RDUIEN_Msk |
+ EMAC_INTEN_TSALMIEN_Msk |
+ EMAC_INTEN_WOLIEN_Msk;
+
+ /* Configure the MAC control register. */
+ EMAC->CTL = EMAC_CTL_STRIPCRC_Msk | EMAC_CTL_RMIIEN_Msk;
+
+ /* Accept packets for us and all broadcast and multicast packets */
+ EMAC->CAMCTL = EMAC_CAMCTL_CMPEN_Msk |
+ EMAC_CAMCTL_AMP_Msk |
+ EMAC_CAMCTL_ABP_Msk;
+ EMAC->CAMEN = 1; // Enable CAM entry 0
+
+ ret= reset_phy();
+
+ EMAC_ENABLE_RX();
+ EMAC_ENABLE_TX();
+ return ret;
+}
+
+
+
+void ETH_halt(void)
+{
+
+ EMAC->CTL &= ~(EMAC_CTL_RXON_Msk | EMAC_CTL_TXON_Msk);
+}
+
+unsigned int m_status;
+
+void EMAC_RX_IRQHandler(void)
+{
+// NU_DEBUGF(("%s ... \r\n", __FUNCTION__));
+ m_status = EMAC->INTSTS & 0xFFFF;
+ EMAC->INTSTS = m_status;
+ if (m_status & EMAC_INTSTS_RXBEIF_Msk) {
+ // Shouldn't goes here, unless descriptor corrupted
+ NU_DEBUGF(("RX descriptor corrupted \r\n"));
+ //return;
+ }
+ // FIX ME: for rx-event, to ack rx_isr into event queue
+ xNetworkCallback('R');
+}
+
+
+void numaker_eth_trigger_rx(void)
+{
+ ETH_TRIGGER_RX();
+}
+
+int numaker_eth_get_rx_buf(uint16_t *len, uint8_t **buf)
+{
+ unsigned int cur_entry, status;
+
+ cur_entry = EMAC->CRXDSA;
+ if ((cur_entry == (uint32_t)cur_rx_desc_ptr) && (!(m_status & EMAC_INTSTS_RDUIF_Msk))) // cur_entry may equal to cur_rx_desc_ptr if RDU occures
+ return -1;
+ status = cur_rx_desc_ptr->status1;
+
+ if(status & OWNERSHIP_EMAC)
+ return -1;
+
+ if (status & RXFD_RXGD) {
+ *buf = cur_rx_desc_ptr->buf;
+ *len = status & 0xFFFF;
+ }
+ return 0;
+}
+
+void numaker_eth_rx_next(void)
+{
+ cur_rx_desc_ptr->status1 = OWNERSHIP_EMAC;
+ cur_rx_desc_ptr = cur_rx_desc_ptr->next;
+}
+
+void EMAC_TX_IRQHandler(void)
+{
+ unsigned int cur_entry, status;
+
+ status = EMAC->INTSTS & 0xFFFF0000;
+ EMAC->INTSTS = status;
+ if(status & EMAC_INTSTS_TXBEIF_Msk) {
+ // Shouldn't goes here, unless descriptor corrupted
+ return;
+ }
+
+ cur_entry = EMAC->CTXDSA;
+
+ while (cur_entry != (uint32_t)fin_tx_desc_ptr) {
+
+ fin_tx_desc_ptr = fin_tx_desc_ptr->next;
+ }
+ // FIX ME: for tx-event, no-op at this stage
+ xNetworkCallback('T');
+}
+
+uint8_t *numaker_eth_get_tx_buf(void)
+{
+ if(cur_tx_desc_ptr->status1 & OWNERSHIP_EMAC)
+ return(NULL);
+ else
+ return(cur_tx_desc_ptr->buf);
+}
+
+void numaker_eth_trigger_tx(uint16_t length, void *p)
+{
+ struct eth_descriptor volatile *desc;
+ cur_tx_desc_ptr->status2 = (unsigned int)length;
+ desc = cur_tx_desc_ptr->next; // in case TX is transmitting and overwrite next pointer before we can update cur_tx_desc_ptr
+ cur_tx_desc_ptr->status1 |= OWNERSHIP_EMAC;
+ cur_tx_desc_ptr = desc;
+
+ ETH_TRIGGER_TX();
+
+}
+
+int numaker_eth_link_ok(void)
+{
+ /* first, a dummy read to latch */
+ mdio_read(CONFIG_PHY_ADDR, MII_BMSR);
+ if(mdio_read(CONFIG_PHY_ADDR, MII_BMSR) & BMSR_LSTATUS)
+ return 1;
+ return 0;
+}
+
+//void numaker_eth_set_cb(eth_callback_t eth_cb, void *userData)
+//{
+// nu_eth_txrx_cb = eth_cb;
+// nu_userData = userData;
+//}
+
+// Provide ethernet devices with a semi-unique MAC address
+void numaker_mac_address(uint8_t *mac)
+{
+ uint32_t uID1;
+ // Fetch word 0
+ uint32_t word0 = *(uint32_t *)0x7F804; // 2KB Data Flash at 0x7F800
+ // Fetch word 1
+ // we only want bottom 16 bits of word1 (MAC bits 32-47)
+ // and bit 9 forced to 1, bit 8 forced to 0
+ // Locally administered MAC, reduced conflicts
+ // http://en.wikipedia.org/wiki/MAC_address
+ uint32_t word1 = *(uint32_t *)0x7F800; // 2KB Data Flash at 0x7F800
+
+ if( word0 == 0xFFFFFFFF ) // Not burn any mac address at 1st 2 words of Data Flash
+ {
+ // with a semi-unique MAC address from the UUID
+ /* Enable FMC ISP function */
+ SYS_UnlockReg();
+ FMC_Open();
+ // = FMC_ReadUID(0);
+ uID1 = FMC_ReadUID(1);
+ word1 = (uID1 & 0x003FFFFF) | ((uID1 & 0x030000) << 6) >> 8;
+ word0 = ((FMC_ReadUID(0) >> 4) << 20) | ((uID1 & 0xFF)<<12) | (FMC_ReadUID(2) & 0xFFF);
+ /* Disable FMC ISP function */
+ FMC_Close();
+ /* Lock protected registers */
+ SYS_LockReg();
+ }
+
+ word1 |= 0x00000200;
+ word1 &= 0x0000FEFF;
+
+ mac[0] = (word1 & 0x0000ff00) >> 8;
+ mac[1] = (word1 & 0x000000ff);
+ mac[2] = (word0 & 0xff000000) >> 24;
+ mac[3] = (word0 & 0x00ff0000) >> 16;
+ mac[4] = (word0 & 0x0000ff00) >> 8;
+ mac[5] = (word0 & 0x000000ff);
+
+ NU_DEBUGF(("mac address %02x-%02x-%02x-%02x-%02x-%02x \r\n", mac[0], mac[1],mac[2],mac[3],mac[4],mac[5]));
+}
+
+void numaker_eth_enable_interrupts(void) {
+ EMAC->INTEN |= EMAC_INTEN_RXIEN_Msk |
+ EMAC_INTEN_TXIEN_Msk ;
+ NVIC_EnableIRQ(EMAC_RX_IRQn);
+ NVIC_EnableIRQ(EMAC_TX_IRQn);
+}
+
+void numaker_eth_disable_interrupts(void) {
+ NVIC_DisableIRQ(EMAC_RX_IRQn);
+ NVIC_DisableIRQ(EMAC_TX_IRQn);
+}
diff --git a/FreeRTOS-Plus/Source/FreeRTOS-Plus-TCP/portable/NetworkInterface/M487/m480_eth.h b/FreeRTOS-Plus/Source/FreeRTOS-Plus-TCP/portable/NetworkInterface/M487/m480_eth.h
new file mode 100644
index 000000000..4e4d98d6d
--- /dev/null
+++ b/FreeRTOS-Plus/Source/FreeRTOS-Plus-TCP/portable/NetworkInterface/M487/m480_eth.h
@@ -0,0 +1,164 @@
+/**************************************************************************//**
+ * @copyright (C) 2019 Nuvoton Technology Corp. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright notice,
+ * this list of conditions and the following disclaimer in the documentation
+ * and/or other materials provided with the distribution.
+ * 3. Neither the name of Nuvoton Technology Corp. nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+ * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+ * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+ * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+ * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*****************************************************************************/
+#include "M480.h"
+#ifndef _M480_ETH_
+#define _M480_ETH_
+
+/* Generic MII registers. */
+
+#define MII_BMCR 0x00 /* Basic mode control register */
+#define MII_BMSR 0x01 /* Basic mode status register */
+#define MII_PHYSID1 0x02 /* PHYS ID 1 */
+#define MII_PHYSID2 0x03 /* PHYS ID 2 */
+#define MII_ADVERTISE 0x04 /* Advertisement control reg */
+#define MII_LPA 0x05 /* Link partner ability reg */
+#define MII_EXPANSION 0x06 /* Expansion register */
+#define MII_DCOUNTER 0x12 /* Disconnect counter */
+#define MII_FCSCOUNTER 0x13 /* False carrier counter */
+#define MII_NWAYTEST 0x14 /* N-way auto-neg test reg */
+#define MII_RERRCOUNTER 0x15 /* Receive error counter */
+#define MII_SREVISION 0x16 /* Silicon revision */
+#define MII_RESV1 0x17 /* Reserved... */
+#define MII_LBRERROR 0x18 /* Lpback, rx, bypass error */
+#define MII_PHYADDR 0x19 /* PHY address */
+#define MII_RESV2 0x1a /* Reserved... */
+#define MII_TPISTATUS 0x1b /* TPI status for 10mbps */
+#define MII_NCONFIG 0x1c /* Network interface config */
+
+/* Basic mode control register. */
+#define BMCR_RESV 0x007f /* Unused... */
+#define BMCR_CTST 0x0080 /* Collision test */
+#define BMCR_FULLDPLX 0x0100 /* Full duplex */
+#define BMCR_ANRESTART 0x0200 /* Auto negotiation restart */
+#define BMCR_ISOLATE 0x0400 /* Disconnect DP83840 from MII */
+#define BMCR_PDOWN 0x0800 /* Powerdown the DP83840 */
+#define BMCR_ANENABLE 0x1000 /* Enable auto negotiation */
+#define BMCR_SPEED100 0x2000 /* Select 100Mbps */
+#define BMCR_LOOPBACK 0x4000 /* TXD loopback bits */
+#define BMCR_RESET 0x8000 /* Reset the DP83840 */
+
+/* Basic mode status register. */
+#define BMSR_ERCAP 0x0001 /* Ext-reg capability */
+#define BMSR_JCD 0x0002 /* Jabber detected */
+#define BMSR_LSTATUS 0x0004 /* Link status */
+#define BMSR_ANEGCAPABLE 0x0008 /* Able to do auto-negotiation */
+#define BMSR_RFAULT 0x0010 /* Remote fault detected */
+#define BMSR_ANEGCOMPLETE 0x0020 /* Auto-negotiation complete */
+#define BMSR_RESV 0x07c0 /* Unused... */
+#define BMSR_10HALF 0x0800 /* Can do 10mbps, half-duplex */
+#define BMSR_10FULL 0x1000 /* Can do 10mbps, full-duplex */
+#define BMSR_100HALF 0x2000 /* Can do 100mbps, half-duplex */
+#define BMSR_100FULL 0x4000 /* Can do 100mbps, full-duplex */
+#define BMSR_100BASE4 0x8000 /* Can do 100mbps, 4k packets */
+
+/* Advertisement control register. */
+#define ADVERTISE_SLCT 0x001f /* Selector bits */
+#define ADVERTISE_CSMA 0x0001 /* Only selector supported */
+#define ADVERTISE_10HALF 0x0020 /* Try for 10mbps half-duplex */
+#define ADVERTISE_10FULL 0x0040 /* Try for 10mbps full-duplex */
+#define ADVERTISE_100HALF 0x0080 /* Try for 100mbps half-duplex */
+#define ADVERTISE_100FULL 0x0100 /* Try for 100mbps full-duplex */
+#define ADVERTISE_100BASE4 0x0200 /* Try for 100mbps 4k packets */
+#define ADVERTISE_RESV 0x1c00 /* Unused... */
+#define ADVERTISE_RFAULT 0x2000 /* Say we can detect faults */
+#define ADVERTISE_LPACK 0x4000 /* Ack link partners response */
+#define ADVERTISE_NPAGE 0x8000 /* Next page bit */
+
+#define RX_DESCRIPTOR_NUM 4 //8 // Max Number of Rx Frame Descriptors
+#define TX_DESCRIPTOR_NUM 2 //4 // Max number of Tx Frame Descriptors
+
+#define PACKET_BUFFER_SIZE 1520
+
+#define CONFIG_PHY_ADDR 1
+
+
+// Frame Descriptor's Owner bit
+#define OWNERSHIP_EMAC 0x80000000 // 1 = EMAC
+//#define OWNERSHIP_CPU 0x7fffffff // 0 = CPU
+
+
+
+// Rx Frame Descriptor Status
+#define RXFD_RXGD 0x00100000 // Receiving Good Packet Received
+#define RXFD_RTSAS 0x00800000 // RX Time Stamp Available
+
+
+// Tx Frame Descriptor's Control bits
+#define TXFD_TTSEN 0x08 // Tx Time Stamp Enable
+#define TXFD_INTEN 0x04 // Interrupt Enable
+#define TXFD_CRCAPP 0x02 // Append CRC
+#define TXFD_PADEN 0x01 // Padding Enable
+
+// Tx Frame Descriptor Status
+#define TXFD_TXCP 0x00080000 // Transmission Completion
+#define TXFD_TTSAS 0x08000000 // TX Time Stamp Available
+
+// Tx/Rx buffer descriptor structure
+struct eth_descriptor;
+struct eth_descriptor {
+ uint32_t status1;
+ uint8_t *buf;
+ uint32_t status2;
+ struct eth_descriptor *next;
+#ifdef TIME_STAMPING
+ uint32_t backup1;
+ uint32_t backup2;
+ uint32_t reserved1;
+ uint32_t reserved2;
+#endif
+};
+
+#ifdef TIME_STAMPING
+
+#define ETH_TS_ENABLE() do{EMAC->TSCTL = EMAC_TSCTL_TSEN_Msk;}while(0)
+#define ETH_TS_START() do{EMAC->TSCTL |= (EMAC_TSCTL_TSMODE_Msk | EMAC_TSCTL_TSIEN_Msk);}while(0)
+s32_t ETH_settime(u32_t sec, u32_t nsec);
+s32_t ETH_gettime(u32_t *sec, u32_t *nsec);
+s32_t ETH_updatetime(u32_t neg, u32_t sec, u32_t nsec);
+s32_t ETH_adjtimex(int ppm);
+void ETH_setinc(void);
+
+#endif
+
+#ifdef NU_TRACE
+#define NU_DEBUGF(x) { printf x; }
+#else
+#define NU_DEBUGF(x)
+#endif
+
+void numaker_set_mac_addr(uint8_t *addr);
+int numaker_eth_init(uint8_t *mac_addr);
+uint8_t *numaker_eth_get_tx_buf(void);
+void numaker_eth_trigger_tx(uint16_t length, void *p);
+int numaker_eth_get_rx_buf(uint16_t *len, uint8_t **buf);
+void numaker_eth_rx_next(void);
+void numaker_eth_trigger_rx(void);
+int numaker_eth_link_ok(void);
+void numaker_mac_address(uint8_t *mac);
+void numaker_eth_enable_interrupts(void);
+void numaker_eth_disable_interrupts(void);
+
+#endif /* _M480_ETH_ */