Dependents:   Nucleo

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers mk7x_eth.c Source File

mk7x_eth.c

Go to the documentation of this file.
00001 /**
00002  * @file mk7x_eth.c
00003  * @brief Freescale Kinetis K70 Ethernet MAC controller
00004  *
00005  * @section License
00006  *
00007  * Copyright (C) 2010-2017 Oryx Embedded SARL. All rights reserved.
00008  *
00009  * This file is part of CycloneTCP Open.
00010  *
00011  * This program is free software; you can redistribute it and/or
00012  * modify it under the terms of the GNU General Public License
00013  * as published by the Free Software Foundation; either version 2
00014  * of the License, or (at your option) any later version.
00015  *
00016  * This program is distributed in the hope that it will be useful,
00017  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00018  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00019  * GNU General Public License for more details.
00020  *
00021  * You should have received a copy of the GNU General Public License
00022  * along with this program; if not, write to the Free Software Foundation,
00023  * Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301, USA.
00024  *
00025  * @author Oryx Embedded SARL (www.oryx-embedded.com)
00026  * @version 1.7.6
00027  **/
00028 
00029 //Switch to the appropriate trace level
00030 #define TRACE_LEVEL NIC_TRACE_LEVEL
00031 
00032 //MK70F12 device?
00033 #if defined(MK70F12)
00034    #include "mk70f12.h"
00035 //MK70F15 device?
00036 #elif defined(MK70F15)
00037    #include "mk70f15.h"
00038 #endif
00039 
00040 //Dependencies
00041 #include "core/net.h"
00042 #include "drivers/mk7x_eth.h"
00043 #include "debug.h"
00044 
00045 //Underlying network interface
00046 static NetInterface *nicDriverInterface;
00047 
00048 //IAR EWARM compiler?
00049 #if defined(__ICCARM__)
00050 
00051 //TX buffer
00052 #pragma data_alignment = 16
00053 static uint8_t txBuffer[MK7X_ETH_TX_BUFFER_COUNT][MK7X_ETH_TX_BUFFER_SIZE];
00054 //RX buffer
00055 #pragma data_alignment = 16
00056 static uint8_t rxBuffer[MK7X_ETH_RX_BUFFER_COUNT][MK7X_ETH_RX_BUFFER_SIZE];
00057 //TX buffer descriptors
00058 #pragma data_alignment = 16
00059 static uint16_t txBufferDesc[MK7X_ETH_TX_BUFFER_COUNT][16];
00060 //RX buffer descriptors
00061 #pragma data_alignment = 16
00062 static uint16_t rxBufferDesc[MK7X_ETH_RX_BUFFER_COUNT][16];
00063 
00064 //ARM or GCC compiler?
00065 #else
00066 
00067 //TX buffer
00068 static uint8_t txBuffer[MK7X_ETH_TX_BUFFER_COUNT][MK7X_ETH_TX_BUFFER_SIZE]
00069    __attribute__((aligned(16)));
00070 //RX buffer
00071 static uint8_t rxBuffer[MK7X_ETH_RX_BUFFER_COUNT][MK7X_ETH_RX_BUFFER_SIZE]
00072    __attribute__((aligned(16)));
00073 //TX buffer descriptors
00074 static uint16_t txBufferDesc[MK7X_ETH_TX_BUFFER_COUNT][16]
00075    __attribute__((aligned(16)));
00076 //RX buffer descriptors
00077 static uint16_t rxBufferDesc[MK7X_ETH_RX_BUFFER_COUNT][16]
00078    __attribute__((aligned(16)));
00079 
00080 #endif
00081 
00082 //TX buffer index
00083 static uint_t txBufferIndex;
00084 //RX buffer index
00085 static uint_t rxBufferIndex;
00086 
00087 
00088 /**
00089  * @brief Kinetis K7x Ethernet MAC driver
00090  **/
00091 
00092 const NicDriver mk7xEthDriver =
00093 {
00094    NIC_TYPE_ETHERNET,
00095    ETH_MTU,
00096    mk7xEthInit,
00097    mk7xEthTick,
00098    mk7xEthEnableIrq,
00099    mk7xEthDisableIrq,
00100    mk7xEthEventHandler,
00101    mk7xEthSendPacket,
00102    mk7xEthSetMulticastFilter,
00103    mk7xEthUpdateMacConfig,
00104    mk7xEthWritePhyReg,
00105    mk7xEthReadPhyReg,
00106    TRUE,
00107    TRUE,
00108    TRUE,
00109    FALSE
00110 };
00111 
00112 
00113 /**
00114  * @brief Kinetis K7x Ethernet MAC initialization
00115  * @param[in] interface Underlying network interface
00116  * @return Error code
00117  **/
00118 
00119 error_t mk7xEthInit(NetInterface *interface)
00120 {
00121    error_t error;
00122    uint32_t value;
00123 
00124    //Debug message
00125    TRACE_INFO("Initializing Kinetis K7x Ethernet MAC...\r\n");
00126 
00127    //Save underlying network interface
00128    nicDriverInterface = interface;
00129 
00130    //Disable MPU
00131    MPU->CESR &= ~MPU_CESR_VLD_MASK;
00132 
00133    //Enable external reference clock
00134    OSC0->CR |= OSC_CR_ERCLKEN_MASK;
00135    //Enable ENET peripheral clock
00136    SIM->SCGC2 |= SIM_SCGC2_ENET_MASK;
00137 
00138    //GPIO configuration
00139    mk7xEthInitGpio(interface);
00140 
00141    //Reset ENET module
00142    ENET->ECR = ENET_ECR_RESET_MASK;
00143    //Wait for the reset to complete
00144    while(ENET->ECR & ENET_ECR_RESET_MASK);
00145 
00146    //Reveive control register
00147    ENET->RCR = ENET_RCR_MAX_FL(1518) | ENET_RCR_RMII_MODE_MASK | ENET_RCR_MII_MODE_MASK;
00148    //Transmit control register
00149    ENET->TCR = 0;
00150    //Configure MDC clock frequency
00151    ENET->MSCR = ENET_MSCR_MII_SPEED(59);
00152 
00153    //PHY transceiver initialization
00154    error = interface->phyDriver->init(interface);
00155    //Failed to initialize PHY transceiver?
00156    if(error)
00157       return error;
00158 
00159    //Set the MAC address (upper 16 bits)
00160    value = interface->macAddr.b[5];
00161    value |= (interface->macAddr.b[4] << 8);
00162    ENET->PAUR = ENET_PAUR_PADDR2(value) | ENET_PAUR_TYPE(0x8808);
00163 
00164    //Set the MAC address (lower 32 bits)
00165    value = interface->macAddr.b[3];
00166    value |= (interface->macAddr.b[2] << 8);
00167    value |= (interface->macAddr.b[1] << 16);
00168    value |= (interface->macAddr.b[0] << 24);
00169    ENET->PALR = ENET_PALR_PADDR1(value);
00170 
00171    //Hash table for unicast address filtering
00172    ENET->IALR = 0;
00173    ENET->IAUR = 0;
00174    //Hash table for multicast address filtering
00175    ENET->GALR = 0;
00176    ENET->GAUR = 0;
00177 
00178    //Disable transmit accelerator functions
00179    ENET->TACC = 0;
00180    //Disable receive accelerator functions
00181    ENET->RACC = 0;
00182 
00183    //Use enhanced buffer descriptors
00184    ENET->ECR = ENET_ECR_EN1588_MASK;
00185    //Clear MIC counters
00186    ENET->MIBC = ENET_MIBC_MIB_CLEAR_MASK;
00187 
00188    //Initialize buffer descriptors
00189    mk7xEthInitBufferDesc(interface);
00190 
00191    //Clear any pending interrupts
00192    ENET->EIR = 0xFFFFFFFF;
00193    //Enable desired interrupts
00194    ENET->EIMR = ENET_EIMR_TXF_MASK | ENET_EIMR_RXF_MASK | ENET_EIMR_EBERR_MASK;
00195 
00196    //Set priority grouping (4 bits for pre-emption priority, no bits for subpriority)
00197    NVIC_SetPriorityGrouping(MK7X_ETH_IRQ_PRIORITY_GROUPING);
00198 
00199    //Configure ENET transmit interrupt priority
00200    NVIC_SetPriority(ENET_Transmit_IRQn, NVIC_EncodePriority(MK7X_ETH_IRQ_PRIORITY_GROUPING,
00201       MK7X_ETH_IRQ_GROUP_PRIORITY, MK7X_ETH_IRQ_SUB_PRIORITY));
00202 
00203    //Configure ENET receive interrupt priority
00204    NVIC_SetPriority(ENET_Receive_IRQn, NVIC_EncodePriority(MK7X_ETH_IRQ_PRIORITY_GROUPING,
00205       MK7X_ETH_IRQ_GROUP_PRIORITY, MK7X_ETH_IRQ_SUB_PRIORITY));
00206 
00207    //Configure ENET error interrupt priority
00208    NVIC_SetPriority(ENET_Error_IRQn, NVIC_EncodePriority(MK7X_ETH_IRQ_PRIORITY_GROUPING,
00209       MK7X_ETH_IRQ_GROUP_PRIORITY, MK7X_ETH_IRQ_SUB_PRIORITY));
00210 
00211    //Enable Ethernet MAC
00212    ENET->ECR |= ENET_ECR_ETHEREN_MASK;
00213    //Instruct the DMA to poll the receive descriptor list
00214    ENET->RDAR = ENET_RDAR_RDAR_MASK;
00215 
00216    //Accept any packets from the upper layer
00217    osSetEvent(&interface->nicTxEvent);
00218 
00219    //Successful initialization
00220    return NO_ERROR;
00221 }
00222 
00223 
00224 //TWR-K70F120M evaluation board?
00225 #if defined(USE_TWR_K70F120M)
00226 
00227 /**
00228  * @brief GPIO configuration
00229  * @param[in] interface Underlying network interface
00230  **/
00231 
00232 void mk7xEthInitGpio(NetInterface *interface)
00233 {
00234    //Enable PORTA and PORTB peripheral clocks
00235    SIM->SCGC5 |= SIM_SCGC5_PORTA_MASK | SIM_SCGC5_PORTB_MASK;
00236 
00237    //Configure RMII0_RXER (PTA5)
00238    PORTA->PCR[5] = PORT_PCR_MUX(4) | PORT_PCR_PE_MASK;
00239    //Configure RMII0_RXD1 (PTA12)
00240    PORTA->PCR[12] = PORT_PCR_MUX(4);
00241    //Configure RMII0_RXD0 (PTA13)
00242    PORTA->PCR[13] = PORT_PCR_MUX(4);
00243    //Configure RMII0_CRS_DV (PTA14)
00244    PORTA->PCR[14] = PORT_PCR_MUX(4);
00245    //Configure RMII0_TXEN (PTA15)
00246    PORTA->PCR[15] = PORT_PCR_MUX(4);
00247    //Configure RMII0_TXD0 (PTA16)
00248    PORTA->PCR[16] = PORT_PCR_MUX(4);
00249    //Configure RMII0_TXD1 (PTA17)
00250    PORTA->PCR[17] = PORT_PCR_MUX(4);
00251 
00252    //Configure RMII0_MDIO (PTB0)
00253    PORTB->PCR[0] = PORT_PCR_MUX(4) | PORT_PCR_PE_MASK | PORT_PCR_PS_MASK;
00254    //Configure RMII0_MDC (PTB1)
00255    PORTB->PCR[1] = PORT_PCR_MUX(4);
00256 }
00257 
00258 #endif
00259 
00260 
00261 /**
00262  * @brief Initialize buffer descriptors
00263  * @param[in] interface Underlying network interface
00264  **/
00265 
00266 void mk7xEthInitBufferDesc(NetInterface *interface)
00267 {
00268    uint_t i;
00269    uint32_t address;
00270 
00271    //Clear TX and RX buffer descriptors
00272    memset(txBufferDesc, 0, sizeof(txBufferDesc));
00273    memset(rxBufferDesc, 0, sizeof(rxBufferDesc));
00274 
00275    //Initialize TX buffer descriptors
00276    for(i = 0; i < MK7X_ETH_TX_BUFFER_COUNT; i++)
00277    {
00278       //Calculate the address of the current TX buffer
00279       address = (uint32_t) txBuffer[i];
00280       //Transmit buffer address
00281       txBufferDesc[i][2] = htobe16(address >> 16);
00282       txBufferDesc[i][3] = htobe16(address & 0xFFFF);
00283       //Generate interrupts
00284       txBufferDesc[i][4] = HTOBE16(ENET_TBD4_INT);
00285    }
00286 
00287    //Mark the last descriptor entry with the wrap flag
00288    txBufferDesc[i - 1][0] |= HTOBE16(ENET_TBD0_W);
00289    //Initialize TX buffer index
00290    txBufferIndex = 0;
00291 
00292    //Initialize RX buffer descriptors
00293    for(i = 0; i < MK7X_ETH_RX_BUFFER_COUNT; i++)
00294    {
00295       //Calculate the address of the current RX buffer
00296       address = (uint32_t) rxBuffer[i];
00297       //The descriptor is initially owned by the DMA
00298       rxBufferDesc[i][0] = HTOBE16(ENET_RBD0_E);
00299       //Receive buffer address
00300       rxBufferDesc[i][2] = htobe16(address >> 16);
00301       rxBufferDesc[i][3] = htobe16(address & 0xFFFF);
00302       //Generate interrupts
00303       rxBufferDesc[i][4] = HTOBE16(ENET_RBD4_INT);
00304    }
00305 
00306    //Mark the last descriptor entry with the wrap flag
00307    rxBufferDesc[i - 1][0] |= HTOBE16(ENET_RBD0_W);
00308    //Initialize RX buffer index
00309    rxBufferIndex = 0;
00310 
00311    //Start location of the TX descriptor list
00312    ENET->TDSR = (uint32_t) txBufferDesc;
00313    //Start location of the RX descriptor list
00314    ENET->RDSR = (uint32_t) rxBufferDesc;
00315    //Maximum receive buffer size
00316    ENET->MRBR = MK7X_ETH_RX_BUFFER_SIZE;
00317 }
00318 
00319 
00320 /**
00321  * @brief Kinetis K7x Ethernet MAC timer handler
00322  *
00323  * This routine is periodically called by the TCP/IP stack to
00324  * handle periodic operations such as polling the link state
00325  *
00326  * @param[in] interface Underlying network interface
00327  **/
00328 
00329 void mk7xEthTick(NetInterface *interface)
00330 {
00331    //Handle periodic operations
00332    interface->phyDriver->tick(interface);
00333 }
00334 
00335 
00336 /**
00337  * @brief Enable interrupts
00338  * @param[in] interface Underlying network interface
00339  **/
00340 
00341 void mk7xEthEnableIrq(NetInterface *interface)
00342 {
00343    //Enable Ethernet MAC interrupts
00344    NVIC_EnableIRQ(ENET_Transmit_IRQn);
00345    NVIC_EnableIRQ(ENET_Receive_IRQn);
00346    NVIC_EnableIRQ(ENET_Error_IRQn);
00347    //Enable Ethernet PHY interrupts
00348    interface->phyDriver->enableIrq(interface);
00349 }
00350 
00351 
00352 /**
00353  * @brief Disable interrupts
00354  * @param[in] interface Underlying network interface
00355  **/
00356 
00357 void mk7xEthDisableIrq(NetInterface *interface)
00358 {
00359    //Disable Ethernet MAC interrupts
00360    NVIC_DisableIRQ(ENET_Transmit_IRQn);
00361    NVIC_DisableIRQ(ENET_Receive_IRQn);
00362    NVIC_DisableIRQ(ENET_Error_IRQn);
00363    //Disable Ethernet PHY interrupts
00364    interface->phyDriver->disableIrq(interface);
00365 }
00366 
00367 
00368 /**
00369  * @brief Ethernet MAC transmit interrupt
00370  **/
00371 
00372 void ENET_Transmit_IRQHandler(void)
00373 {
00374    bool_t flag;
00375 
00376    //Enter interrupt service routine
00377    osEnterIsr();
00378 
00379    //This flag will be set if a higher priority task must be woken
00380    flag = FALSE;
00381 
00382    //A packet has been transmitted?
00383    if(ENET->EIR & ENET_EIR_TXF_MASK)
00384    {
00385       //Clear TXF interrupt flag
00386       ENET->EIR = ENET_EIR_TXF_MASK;
00387 
00388       //Check whether the TX buffer is available for writing
00389       if(!(txBufferDesc[txBufferIndex][0] & HTOBE16(ENET_TBD0_R)))
00390       {
00391          //Notify the TCP/IP stack that the transmitter is ready to send
00392          flag = osSetEventFromIsr(&nicDriverInterface->nicTxEvent);
00393       }
00394 
00395       //Instruct the DMA to poll the transmit descriptor list
00396       ENET->TDAR = ENET_TDAR_TDAR_MASK;
00397    }
00398 
00399    //Leave interrupt service routine
00400    osExitIsr(flag);
00401 }
00402 
00403 
00404 /**
00405  * @brief Ethernet MAC receive interrupt
00406  **/
00407 
00408 void ENET_Receive_IRQHandler(void)
00409 {
00410    bool_t flag;
00411 
00412    //Enter interrupt service routine
00413    osEnterIsr();
00414 
00415    //This flag will be set if a higher priority task must be woken
00416    flag = FALSE;
00417 
00418    //A packet has been received?
00419    if(ENET->EIR & ENET_EIR_RXF_MASK)
00420    {
00421       //Disable RXF interrupt
00422       ENET->EIMR &= ~ENET_EIMR_RXF_MASK;
00423 
00424       //Set event flag
00425       nicDriverInterface->nicEvent = TRUE;
00426       //Notify the TCP/IP stack of the event
00427       flag = osSetEventFromIsr(&netEvent);
00428    }
00429 
00430    //Leave interrupt service routine
00431    osExitIsr(flag);
00432 }
00433 
00434 
00435 /**
00436  * @brief Ethernet MAC error interrupt
00437  **/
00438 
00439 void ENET_Error_IRQHandler(void)
00440 {
00441    bool_t flag;
00442 
00443    //Enter interrupt service routine
00444    osEnterIsr();
00445 
00446    //This flag will be set if a higher priority task must be woken
00447    flag = FALSE;
00448 
00449    //System bus error?
00450    if(ENET->EIR & ENET_EIR_EBERR_MASK)
00451    {
00452       //Disable EBERR interrupt
00453       ENET->EIMR &= ~ENET_EIMR_EBERR_MASK;
00454 
00455       //Set event flag
00456       nicDriverInterface->nicEvent = TRUE;
00457       //Notify the TCP/IP stack of the event
00458       flag |= osSetEventFromIsr(&netEvent);
00459    }
00460 
00461    //Leave interrupt service routine
00462    osExitIsr(flag);
00463 }
00464 
00465 
00466 /**
00467  * @brief Kinetis K7x Ethernet MAC event handler
00468  * @param[in] interface Underlying network interface
00469  **/
00470 
00471 void mk7xEthEventHandler(NetInterface *interface)
00472 {
00473    error_t error;
00474    uint32_t status;
00475 
00476    //Read interrupt event register
00477    status = ENET->EIR;
00478 
00479    //Packet received?
00480    if(status & ENET_EIR_RXF_MASK)
00481    {
00482       //Clear RXF interrupt flag
00483       ENET->EIR = ENET_EIR_RXF_MASK;
00484 
00485       //Process all pending packets
00486       do
00487       {
00488          //Read incoming packet
00489          error = mk7xEthReceivePacket(interface);
00490 
00491          //No more data in the receive buffer?
00492       } while(error != ERROR_BUFFER_EMPTY);
00493    }
00494 
00495    //System bus error?
00496    if(status & ENET_EIR_EBERR_MASK)
00497    {
00498       //Clear EBERR interrupt flag
00499       ENET->EIR = ENET_EIR_EBERR_MASK;
00500 
00501       //Disable Ethernet MAC
00502       ENET->ECR &= ~ENET_ECR_ETHEREN_MASK;
00503       //Reset buffer descriptors
00504       mk7xEthInitBufferDesc(interface);
00505       //Resume normal operation
00506       ENET->ECR |= ENET_ECR_ETHEREN_MASK;
00507       //Instruct the DMA to poll the receive descriptor list
00508       ENET->RDAR = ENET_RDAR_RDAR_MASK;
00509    }
00510 
00511    //Re-enable Ethernet MAC interrupts
00512    ENET->EIMR = ENET_EIMR_TXF_MASK | ENET_EIMR_RXF_MASK | ENET_EIMR_EBERR_MASK;
00513 }
00514 
00515 
00516 /**
00517  * @brief Send a packet
00518  * @param[in] interface Underlying network interface
00519  * @param[in] buffer Multi-part buffer containing the data to send
00520  * @param[in] offset Offset to the first data byte
00521  * @return Error code
00522  **/
00523 
00524 error_t mk7xEthSendPacket(NetInterface *interface,
00525    const NetBuffer *buffer, size_t offset)
00526 {
00527    size_t length;
00528 
00529    //Retrieve the length of the packet
00530    length = netBufferGetLength(buffer) - offset;
00531 
00532    //Check the frame length
00533    if(length > MK7X_ETH_TX_BUFFER_SIZE)
00534    {
00535       //The transmitter can accept another packet
00536       osSetEvent(&interface->nicTxEvent);
00537       //Report an error
00538       return ERROR_INVALID_LENGTH;
00539    }
00540 
00541    //Make sure the current buffer is available for writing
00542    if(txBufferDesc[txBufferIndex][0] & HTOBE16(ENET_TBD0_R))
00543       return ERROR_FAILURE;
00544 
00545    //Copy user data to the transmit buffer
00546    netBufferRead(txBuffer[txBufferIndex], buffer, offset, length);
00547 
00548    //Set frame length
00549    txBufferDesc[txBufferIndex][1] = HTOBE16(length);
00550    //Clear BDU flag
00551    txBufferDesc[txBufferIndex][8] = 0;
00552 
00553    //Check current index
00554    if(txBufferIndex < (MK7X_ETH_TX_BUFFER_COUNT - 1))
00555    {
00556       //Give the ownership of the descriptor to the DMA engine
00557       txBufferDesc[txBufferIndex][0] = HTOBE16(ENET_TBD0_R |
00558          ENET_TBD0_L | ENET_TBD0_TC);
00559 
00560       //Point to the next buffer
00561       txBufferIndex++;
00562    }
00563    else
00564    {
00565       //Give the ownership of the descriptor to the DMA engine
00566       txBufferDesc[txBufferIndex][0] = HTOBE16(ENET_TBD0_R |
00567          ENET_TBD0_W | ENET_TBD0_L | ENET_TBD0_TC);
00568 
00569       //Wrap around
00570       txBufferIndex = 0;
00571    }
00572 
00573    //Instruct the DMA to poll the transmit descriptor list
00574    ENET->TDAR = ENET_TDAR_TDAR_MASK;
00575 
00576    //Check whether the next buffer is available for writing
00577    if(!(txBufferDesc[txBufferIndex][0] & HTOBE16(ENET_TBD0_R)))
00578    {
00579       //The transmitter can accept another packet
00580       osSetEvent(&interface->nicTxEvent);
00581    }
00582 
00583    //Successful processing
00584    return NO_ERROR;
00585 }
00586 
00587 
00588 /**
00589  * @brief Receive a packet
00590  * @param[in] interface Underlying network interface
00591  * @return Error code
00592  **/
00593 
00594 error_t mk7xEthReceivePacket(NetInterface *interface)
00595 {
00596    error_t error;
00597    size_t n;
00598 
00599    //Make sure the current buffer is available for reading
00600    if(!(rxBufferDesc[rxBufferIndex][0] & HTOBE16(ENET_RBD0_E)))
00601    {
00602       //The frame should not span multiple buffers
00603       if(rxBufferDesc[rxBufferIndex][0] & HTOBE16(ENET_RBD0_L))
00604       {
00605          //Check whether an error occurred
00606          if(!(rxBufferDesc[rxBufferIndex][0] & HTOBE16(ENET_RBD0_LG |
00607             ENET_RBD0_NO | ENET_RBD0_CR | ENET_RBD0_OV | ENET_RBD0_TR)))
00608          {
00609             //Retrieve the length of the frame
00610             n = betoh16(rxBufferDesc[rxBufferIndex][1]);
00611             //Limit the number of data to read
00612             n = MIN(n, MK7X_ETH_RX_BUFFER_SIZE);
00613 
00614             //Pass the packet to the upper layer
00615             nicProcessPacket(interface, rxBuffer[rxBufferIndex], n);
00616 
00617             //Valid packet received
00618             error = NO_ERROR;
00619          }
00620          else
00621          {
00622             //The received packet contains an error
00623             error = ERROR_INVALID_PACKET;
00624          }
00625       }
00626       else
00627       {
00628          //The packet is not valid
00629          error = ERROR_INVALID_PACKET;
00630       }
00631 
00632       //Clear BDU flag
00633       rxBufferDesc[rxBufferIndex][8] = 0;
00634 
00635       //Check current index
00636       if(rxBufferIndex < (MK7X_ETH_RX_BUFFER_COUNT - 1))
00637       {
00638          //Give the ownership of the descriptor back to the DMA engine
00639          rxBufferDesc[rxBufferIndex][0] = HTOBE16(ENET_RBD0_E);
00640          //Point to the next buffer
00641          rxBufferIndex++;
00642       }
00643       else
00644       {
00645          //Give the ownership of the descriptor back to the DMA engine
00646          rxBufferDesc[rxBufferIndex][0] = HTOBE16(ENET_RBD0_E | ENET_RBD0_W);
00647          //Wrap around
00648          rxBufferIndex = 0;
00649       }
00650 
00651       //Instruct the DMA to poll the receive descriptor list
00652       ENET->RDAR = ENET_RDAR_RDAR_MASK;
00653    }
00654    else
00655    {
00656       //No more data in the receive buffer
00657       error = ERROR_BUFFER_EMPTY;
00658    }
00659 
00660    //Return status code
00661    return error;
00662 }
00663 
00664 
00665 /**
00666  * @brief Configure multicast MAC address filtering
00667  * @param[in] interface Underlying network interface
00668  * @return Error code
00669  **/
00670 
00671 error_t mk7xEthSetMulticastFilter(NetInterface *interface)
00672 {
00673    uint_t i;
00674    uint_t k;
00675    uint32_t crc;
00676    uint32_t hashTable[2];
00677    MacFilterEntry *entry;
00678 
00679    //Debug message
00680    TRACE_DEBUG("Updating Kinetis K7x hash table...\r\n");
00681 
00682    //Clear hash table
00683    hashTable[0] = 0;
00684    hashTable[1] = 0;
00685 
00686    //The MAC filter table contains the multicast MAC addresses
00687    //to accept when receiving an Ethernet frame
00688    for(i = 0; i < MAC_MULTICAST_FILTER_SIZE; i++)
00689    {
00690       //Point to the current entry
00691       entry = &interface->macMulticastFilter[i];
00692 
00693       //Valid entry?
00694       if(entry->refCount > 0)
00695       {
00696          //Compute CRC over the current MAC address
00697          crc = mk7xEthCalcCrc(&entry->addr, sizeof(MacAddr));
00698 
00699          //The upper 6 bits in the CRC register are used to index the
00700          //contents of the hash table
00701          k = (crc >> 26) & 0x3F;
00702 
00703          //Update hash table contents
00704          hashTable[k / 32] |= (1 << (k % 32));
00705       }
00706    }
00707 
00708    //Write the hash table
00709    ENET->GALR = hashTable[0];
00710    ENET->GAUR = hashTable[1];
00711 
00712    //Debug message
00713    TRACE_DEBUG("  GALR = %08" PRIX32 "\r\n", ENET->GALR);
00714    TRACE_DEBUG("  GAUR = %08" PRIX32 "\r\n", ENET->GAUR);
00715 
00716    //Successful processing
00717    return NO_ERROR;
00718 }
00719 
00720 
00721 /**
00722  * @brief Adjust MAC configuration parameters for proper operation
00723  * @param[in] interface Underlying network interface
00724  * @return Error code
00725  **/
00726 
00727 error_t mk7xEthUpdateMacConfig(NetInterface *interface)
00728 {
00729    //Disable Ethernet MAC while modifying configuration registers
00730    ENET->ECR &= ~ENET_ECR_ETHEREN_MASK;
00731 
00732    //10BASE-T or 100BASE-TX operation mode?
00733    if(interface->linkSpeed == NIC_LINK_SPEED_100MBPS)
00734    {
00735       //100 Mbps operation
00736       ENET->RCR &= ~ENET_RCR_RMII_10T_MASK;
00737    }
00738    else
00739    {
00740       //10 Mbps operation
00741       ENET->RCR |= ENET_RCR_RMII_10T_MASK;
00742    }
00743 
00744    //Half-duplex or full-duplex mode?
00745    if(interface->duplexMode == NIC_FULL_DUPLEX_MODE)
00746    {
00747       //Full-duplex mode
00748       ENET->TCR |= ENET_TCR_FDEN_MASK;
00749       //Receive path operates independently of transmit
00750       ENET->RCR &= ~ENET_RCR_DRT_MASK;
00751    }
00752    else
00753    {
00754       //Half-duplex mode
00755       ENET->TCR &= ~ENET_TCR_FDEN_MASK;
00756       //Disable reception of frames while transmitting
00757       ENET->RCR |= ENET_RCR_DRT_MASK;
00758    }
00759 
00760    //Reset buffer descriptors
00761    mk7xEthInitBufferDesc(interface);
00762 
00763    //Re-enable Ethernet MAC
00764    ENET->ECR |= ENET_ECR_ETHEREN_MASK;
00765    //Instruct the DMA to poll the receive descriptor list
00766    ENET->RDAR = ENET_RDAR_RDAR_MASK;
00767 
00768    //Successful processing
00769    return NO_ERROR;
00770 }
00771 
00772 
00773 /**
00774  * @brief Write PHY register
00775  * @param[in] phyAddr PHY address
00776  * @param[in] regAddr Register address
00777  * @param[in] data Register value
00778  **/
00779 
00780 void mk7xEthWritePhyReg(uint8_t phyAddr, uint8_t regAddr, uint16_t data)
00781 {
00782    uint32_t value;
00783 
00784    //Set up a write operation
00785    value = ENET_MMFR_ST(1) | ENET_MMFR_OP(1) | ENET_MMFR_TA(2);
00786    //PHY address
00787    value |= ENET_MMFR_PA(phyAddr);
00788    //Register address
00789    value |= ENET_MMFR_RA(regAddr);
00790    //Register value
00791    value |= ENET_MMFR_DATA(data);
00792 
00793    //Clear MII interrupt flag
00794    ENET->EIR = ENET_EIR_MII_MASK;
00795    //Start a write operation
00796    ENET->MMFR = value;
00797    //Wait for the write to complete
00798    while(!(ENET->EIR & ENET_EIR_MII_MASK));
00799 }
00800 
00801 
00802 /**
00803  * @brief Read PHY register
00804  * @param[in] phyAddr PHY address
00805  * @param[in] regAddr Register address
00806  * @return Register value
00807  **/
00808 
00809 uint16_t mk7xEthReadPhyReg(uint8_t phyAddr, uint8_t regAddr)
00810 {
00811    uint32_t value;
00812 
00813    //Set up a read operation
00814    value = ENET_MMFR_ST(1) | ENET_MMFR_OP(2) | ENET_MMFR_TA(2);
00815    //PHY address
00816    value |= ENET_MMFR_PA(phyAddr);
00817    //Register address
00818    value |= ENET_MMFR_RA(regAddr);
00819 
00820    //Clear MII interrupt flag
00821    ENET->EIR = ENET_EIR_MII_MASK;
00822    //Start a read operation
00823    ENET->MMFR = value;
00824    //Wait for the read to complete
00825    while(!(ENET->EIR & ENET_EIR_MII_MASK));
00826 
00827    //Return PHY register contents
00828    return ENET->MMFR & ENET_MMFR_DATA_MASK;
00829 }
00830 
00831 
00832 /**
00833  * @brief CRC calculation
00834  * @param[in] data Pointer to the data over which to calculate the CRC
00835  * @param[in] length Number of bytes to process
00836  * @return Resulting CRC value
00837  **/
00838 
00839 uint32_t mk7xEthCalcCrc(const void *data, size_t length)
00840 {
00841    uint_t i;
00842    uint_t j;
00843 
00844    //Point to the data over which to calculate the CRC
00845    const uint8_t *p = (uint8_t *) data;
00846    //CRC preset value
00847    uint32_t crc = 0xFFFFFFFF;
00848 
00849    //Loop through data
00850    for(i = 0; i < length; i++)
00851    {
00852       //Update CRC value
00853       crc ^= p[i];
00854       //The message is processed bit by bit
00855       for(j = 0; j < 8; j++)
00856       {
00857          if(crc & 0x00000001)
00858             crc = (crc >> 1) ^ 0xEDB88320;
00859          else
00860             crc = crc >> 1;
00861       }
00862    }
00863 
00864    //Return CRC value
00865    return crc;
00866 }
00867