This thread has been locked.

If you have a related question, please click the "Ask a related question" button in the top right corner. The newly created question will be automatically linked to this question.

[参考译文] TMS320F28384D:在两个内核之间传输数据(从 CAN 接收数据并通过以太网发送数据)

Guru**** 2386600 points
请注意,本文内容源自机器翻译,可能存在语法或其它翻译错误,仅供参考。如需获取准确内容,请参阅链接中的英语原文或自行翻译。

https://e2e.ti.com/support/microcontrollers/c2000-microcontrollers-group/c2000/f/c2000-microcontrollers-forum/1128166/tms320f28384d-transfer-data-between-two-core-receive-data-from-can-and-send-it-through-ethernet

器件型号:TMS320F28384D

//#############################################################################
//
// FILE:   can_ex5_transmit_receive.c
//
// TITLE:   CAN Configuration for Transmit and Receive.
//
//! \addtogroup driver_example_list
//! <h1> CAN Transmit and Receive Configurations </h1>
//!
//! This example shows the basic setup of CAN in order to transmit or receive
//! messages on the CAN bus with a specific Message ID. The CAN Controller is
//! configured according to the selection of the define.
//!
//! When the TRANSMIT define is selected, the CAN Controller acts as a
//! Transmitter and sends data to the second CAN Controller connected
//! externally.If TRANMSIT is not defined the CAN Controller acts as a Receiver
//! and waits for message to be transmitted by the External CAN Controller.
//! Please refer to the appnote Programming Examples and Debug Strategies 
//! for the DCAN Module (www.ti.com/lit/SPRACE5) for useful information
//! about this example
//!
//! \note CAN modules on the device need to be connected to via CAN
//!       transceivers.
//!
//! \b Hardware \b Required \n
//!  - A C2000 board with CAN transceiver.
//!
//! \b External \b Connections \n
//!  - ControlCARD CANA is on DEVICE_GPIO_PIN_CANTXA (CANTXA)
//!  - and DEVICE_GPIO_PIN_CANRXA (CANRXA)
//!
//! \b Watch \b Variables \b Transmit \Configuration \n
//!  - MSGCOUNT   - Adjust to set the number of messages
//!  - txMsgCount - A counter for the number of messages sent
//!  - txMsgData  - An array with the data being sent
//!  - errorFlag  - A flag that indicates an error has occurred
//!  - rxMsgCount - Has the initial value as No. of Messages to be received
//!                 and decrements with each message.
//!
//
//#############################################################################

//
// Included Files
//
#include "driverlib.h"
#include "device.h"

//
// Comment to Make the CAN Controller work as a Receiver.
//
//#define TRANSMIT

//
// Defines
//
#ifdef TRANSMIT
#define TX_MSG_OBJ_ID    1
#else
#define RX_MSG_OBJ_ID    1
#endif
#define MSG_DATA_LENGTH  8
#define MSGCOUNT        10000000000

//!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
#define IPC_CMD_READ_MEM   0x1001
#define IPC_CMD_RESP       0x2001

#define TEST_PASS          0x5555
#define TEST_FAIL          0xAAAA


#define PACKET_LENGTH 10
#pragma DATA_SECTION(packetData, "MSGRAM_CPU_TO_CM")
uint8_t packetData[PACKET_LENGTH];
uint32_t pass;
uint32_t readData[10];

//!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

//
// Globals
//
#ifdef TRANSMIT
volatile uint32_t txMsgCount = 0;
uint32_t txMsgSuccessful  = 1;
uint16_t txMsgData[4];
#else
volatile uint32_t rxMsgCount = MSGCOUNT;
uint8_t els;
uint8_t fi;
uint16_t rxMsgData[8];

#endif
volatile unsigned long i;
volatile uint32_t errorFlag = 0;

//
// Function Prototypes
//
__interrupt void canaISR(void);

//
// Main
//
void main(void)
{
    //!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

        int i;
        IPC_MessageQueue_t messageQueue;
        IPC_Message_t      TxMsg, RxMsg;

    //
    // Initialize device clock and peripherals
    //
    Device_init();


    ////////////////////
    Device_bootCM(BOOTMODE_BOOT_TO_S0RAM);
    /////////////////////


    //
    // Initialize GPIO and configure GPIO pins for CANTX/CANRX
    // on module A.
    //
    Device_initGPIO();

    /////////////////////////////////
    SysCtl_setEnetClk(SYSCTL_ENETCLKOUT_DIV_2, SYSCTL_SOURCE_SYSPLL);
   // SysCtl_setEnetClk(SYSCTL_ENETCLKOUT_DIV_2, SYSCTL_SOURCE_SYSPLL);
    /////////////////////////////////

    GPIO_setPinConfig(DEVICE_GPIO_CFG_CANRXA);
    GPIO_setPinConfig(DEVICE_GPIO_CFG_CANTXA);

    /////////////////////////////////////////////

    GPIO_setPinConfig(GPIO_42_ENET_MDIO_CLK);
    GPIO_setPinConfig(GPIO_43_ENET_MDIO_DATA);
    GPIO_setPinConfig(GPIO_40_ENET_MII_CRS);
    GPIO_setPinConfig(GPIO_41_ENET_MII_COL);
    GPIO_setPinConfig(GPIO_75_ENET_MII_TX_DATA0);
    GPIO_setPinConfig(GPIO_60_ENET_MII_TX_DATA1);
    GPIO_setPinConfig(GPIO_61_ENET_MII_TX_DATA2);
    GPIO_setPinConfig(GPIO_62_ENET_MII_TX_DATA3);
    GPIO_setPinConfig(GPIO_45_ENET_MII_TX_EN);
    GPIO_setPinConfig(GPIO_63_ENET_MII_RX_DATA0);
    GPIO_setPinConfig(GPIO_53_ENET_MII_RX_DATA1);
    GPIO_setPinConfig(GPIO_54_ENET_MII_RX_DATA2);
    GPIO_setPinConfig(GPIO_66_ENET_MII_RX_DATA3);
    GPIO_setPinConfig(GPIO_65_ENET_MII_RX_ERR);
    GPIO_setPinConfig(GPIO_64_ENET_MII_RX_DV);
    GPIO_setPinConfig(GPIO_44_ENET_MII_TX_CLK);
    GPIO_setPinConfig(GPIO_49_ENET_MII_RX_CLK);
    GPIO_setDirectionMode(68, GPIO_DIR_MODE_OUT);
    GPIO_setPadConfig(68, GPIO_PIN_TYPE_PULLUP);
    GPIO_writePin(68,1);
    GPIO_setDirectionMode(57, GPIO_DIR_MODE_OUT);
    GPIO_setPadConfig(57, GPIO_PIN_TYPE_PULLUP);
    GPIO_writePin(57,1);

    /////////////////////////////////////////////


    //
    // Allocated shared peripheral to C28x
    //
    SysCtl_allocateSharedPeripheral(SYSCTL_PALLOCATE_CAN_A,0x0U);
 //   SysCtl_allocateSharedPeripheral(SYSCTL_PALLOCATE_CAN_B,0x0U);

    //
    // Initialize the CAN controllers
    //
    CAN_initModule(CANA_BASE);

    //
    // Set up the CAN bus bit rate to 500kHz for each module
    // Refer to the Driver Library User Guide for information on how to set
    // tighter timing control. Additionally, consult the device data sheet
    // for more information about the CAN module clocking.
    //
    CAN_setBitRate(CANA_BASE, DEVICE_SYSCLK_FREQ, 500000, 16);

    //
    // Enable interrupts on the CAN A peripheral.
    //
    CAN_enableInterrupt(CANA_BASE, CAN_INT_IE0 | CAN_INT_ERROR |
                        CAN_INT_STATUS);

    //
    // Initialize PIE and clear PIE registers. Disables CPU interrupts.
    //
    Interrupt_initModule();

    //
    // Initialize the PIE vector table with pointers to the shell Interrupt
    // Service Routines (ISR).
    //
    Interrupt_initVectorTable();

    //
    // Enable Global Interrupt (INTM) and realtime interrupt (DBGM)


    //!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
    IPC_clearFlagLtoR(IPC_CPU1_L_CM_R, IPC_FLAG_ALL);

    IPC_initMessageQueue(IPC_CPU1_L_CM_R, &messageQueue, IPC_INT1, IPC_INT1);

    IPC_sync(IPC_CPU1_L_CM_R, IPC_FLAG31);
    //!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

    //
    EINT;
    ERTM;

    //!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

    for(i=0; i<10; i++)
       {
           readData[i] = i;
       }

       //
       // Update the message
       //
       TxMsg.command = IPC_CMD_READ_MEM;
       TxMsg.address = (uint32_t)readData;
       TxMsg.dataw1  = 10;  // Using dataw1 as data length
       TxMsg.dataw2  = 1;   // Message identifier


       //
       // Send message to the queue
       // Since C28x and CM does not share the same address space for shared RAM,
       // ADDRESS_CORRECTION is enabled
       //
       IPC_sendMessageToQueue(IPC_CPU1_L_CM_R, &messageQueue, IPC_ADDR_CORRECTION_ENABLE,
                              &TxMsg, IPC_BLOCKING_CALL);

       //
       // Read message from the queue
       // Return message from CM does not use the address field, hence
       // ADDRESS_COREECTION feature is not used
       //

       IPC_readMessageFromQueue(IPC_CPU1_L_CM_R, &messageQueue, IPC_ADDR_CORRECTION_DISABLE,
                                &RxMsg, IPC_BLOCKING_CALL);

       if((RxMsg.command == IPC_CMD_RESP) && (RxMsg.dataw1 == TEST_PASS) && (RxMsg.dataw2 == 1))
           pass = 1;
       else
           pass = 0;


    //!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
    //
    // Interrupts that are used in this example are re-mapped to
    // ISR functions found within this file.
    // This registers the interrupt handler in PIE vector table.
    //
    Interrupt_register(INT_CANA0,&canaISR);

    //
    // Enable the CAN-A interrupt signal
    //
    Interrupt_enable(INT_CANA0);

    CAN_enableGlobalInterrupt(CANA_BASE, CAN_GLOBAL_INT_CANINT0);

#ifdef TRANSMIT
    //
    // Initialize the transmit message object used for sending CAN messages.
    // Message Object Parameters:
    //      CAN Module: A
    //      Message Object ID Number: 1
    //      Message Identifier: 0x15555555
    //      Message Frame: Extended
    //      Message Type: Transmit
    //      Message ID Mask: 0x0
    //      Message Object Flags: None
    //      Message Data Length: 4 Bytes
    //
    CAN_setupMessageObject(CANA_BASE, TX_MSG_OBJ_ID, 0x15555555,
                           CAN_MSG_FRAME_EXT, CAN_MSG_OBJ_TYPE_TX, 0,
                           CAN_MSG_OBJ_TX_INT_ENABLE, MSG_DATA_LENGTH);
    //
    // Initialize the transmit message object data buffer to be sent
    //
    txMsgData[0] = 0x12;
    txMsgData[1] = 0x34;
    txMsgData[2] = 0x56;
    txMsgData[3] = 0x78;
#else
    //
    // Initialize the receive message object used for receiving CAN messages.
    // Message Object Parameters:
    //      CAN Module: A
    //      Message Object ID Number: 1
    //      Message Identifier: 0x15555555
    //      Message Frame: Extended
    //      Message Type: Receive
    //      Message ID Mask: 0x0
    //      Message Object Flags: Receive Interrupt
    //      Message Data Length: 4 Bytes (Note that DLC field is a "don't care"
    //      for a Receive mailbox
    //
    CAN_setupMessageObject(CANA_BASE, RX_MSG_OBJ_ID, 0x15555555,
                           CAN_MSG_FRAME_EXT, CAN_MSG_OBJ_TYPE_RX, 0,
                           CAN_MSG_OBJ_RX_INT_ENABLE, MSG_DATA_LENGTH);
#endif

    //
    // Start CAN module A operations
    //
    CAN_startModule(CANA_BASE);

#ifdef TRANSMIT
    //
    // Transmit messages from CAN-A.
    //
    for(i = 0; i < MSGCOUNT; i++)
    {
        //
        // Check the error flag to see if errors occurred
        //
        if(errorFlag)
        {
            asm("   ESTOP0");
        }

        //
        // Transmit the message.
        //
        CAN_sendMessage(CANA_BASE, TX_MSG_OBJ_ID, MSG_DATA_LENGTH,
                        txMsgData);

        //
        // Delay 0.25 second before continuing
        //
        DEVICE_DELAY_US(250000);

        while(txMsgSuccessful);
        //
        // Increment the value in the transmitted message data.
        //
        txMsgData[0] += 0x01;
        txMsgData[1] += 0x01;
        txMsgData[2] += 0x01;
        txMsgData[3] += 0x01;

        //
        // Reset data if exceeds a byte
        //
        if(txMsgData[0] > 0xFF)
        {
            txMsgData[0] = 0;
        }
        if(txMsgData[1] > 0xFF)
        {
            txMsgData[1] = 0;
        }
        if(txMsgData[2] > 0xFF)
        {
            txMsgData[2] = 0;
        }
        if(txMsgData[3] > 0xFF)
        {
            txMsgData[3] = 0;
        }

        //
        // Update the flag for next message.
        //
        txMsgSuccessful  = 1;
    }
#else
    //
    // Loop to keep receiving data from another CAN Controller.
    //
    while(rxMsgCount)
    {
    }
#endif

    //
    // Stop application after completion.
    //
    asm("   ESTOP0");
    //!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
    while(1);
    //!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
}

//
// CAN A ISR - The interrupt service routine called when a CAN interrupt is
//             triggered on CAN module A.
//
__interrupt void
canaISR(void)
{
    uint32_t status;

    //
    // Read the CAN-B interrupt status to find the cause of the interrupt
    //
    status = CAN_getInterruptCause(CANA_BASE);

    //
    // If the cause is a controller status interrupt, then get the status
    //
    if(status == CAN_INT_INT0ID_STATUS)
    {
        //
        // Read the controller status.  This will return a field of status
        // error bits that can indicate various errors.  Error processing
        // is not done in this example for simplicity.  Refer to the
        // API documentation for details about the error status bits.
        // The act of reading this status will clear the interrupt.
        //
        status = CAN_getStatus(CANA_BASE);

        //
        // Check to see if an error occurred.
        //
#ifdef TRANSMIT
        if(((status  & ~(CAN_STATUS_TXOK)) != CAN_STATUS_LEC_MSK) &&
           ((status  & ~(CAN_STATUS_TXOK)) != CAN_STATUS_LEC_NONE))
#else
        if(((status  & ~(CAN_STATUS_RXOK)) != CAN_STATUS_LEC_MSK) &&
           ((status  & ~(CAN_STATUS_RXOK)) != CAN_STATUS_LEC_NONE))
#endif
        {
            //
            // Set a flag to indicate some errors may have occurred.
            //
            errorFlag = 1;
        }
    }
#ifdef TRANSMIT
    else if(status == TX_MSG_OBJ_ID)
    {
        //
        // Getting to this point means that the TX interrupt occurred on
        // message object 1, and the message TX is complete.  Clear the
        // message object interrupt.
        //
        CAN_clearInterruptStatus(CANA_BASE, TX_MSG_OBJ_ID);

        //
        // Increment a counter to keep track of how many messages have been
        // transmitted. In a real application this could be used to set flags to
        // indicate when a message is transmitted.
        //
        txMsgCount++;

        //
        // Since the message was transmitted, clear any error flags.
        //
        errorFlag = 0;

        //
        // Clear the message transmitted successful Flag.
        //
        txMsgSuccessful  = 0;
    }
#else
    else if(status == RX_MSG_OBJ_ID)
    {
        //
        // Get the received message
        //
        CAN_readMessage(CANA_BASE, RX_MSG_OBJ_ID, rxMsgData);

        //
        // Getting to this point means that the RX interrupt occurred on
        // message object 1, and the message RX is complete.  Clear the
        // message object interrupt.
        //
        CAN_clearInterruptStatus(CANA_BASE, RX_MSG_OBJ_ID);

        //
        // Decrement the counter after a message has been received.
        //
        rxMsgCount--;

        //
        // Since the message was received, clear any error flags.
        //
        errorFlag = 0;
    }
#endif
    //
    // If something unexpected caused the interrupt, this would handle it.
    //
    else
    {
        //
        // Spurious interrupt handling can go here.
        //
    }

    //
    // Clear the global interrupt flag for the CAN interrupt line
    //
    CAN_clearGlobalInterruptStatus(CANA_BASE, CAN_GLOBAL_INT_CANINT0);

    //
    // Acknowledge this interrupt located in group 9
    //
    Interrupt_clearACKGroup(INTERRUPT_ACK_GROUP9);
}

//
// End of File
//

我在这里附加了我使用的代码。我有 CAN、远程处理器通信和以太网的组合代码。我想从 CAN 接收数据并通过以太网发送数据、请在这方面提供帮助。 (我不熟悉 TI 控制器编程)如果我的意思错误、请为我的确切应用提供示例。提前感谢!

//###########################################################################
//
// FILE:   enet_lwip.c
//
// TITLE:  lwIP based Ethernet Example.
//
// Example to demonstrate UDP socket (for daikin customer)
// buf_rx,buf_tx are the watch variables which can be used or updated in the
// main application based on the requirement.
// 
// Test setup
//
// F2838x Control Card connected to a PC/laptop  on the Ethernet port.
// PC/laptop runs the SocketTest/â€TmPacket Senderâ€Tm software, configured for the IP Address and port . \
// Keywords ‘STARTâ€Tm and ‘STOPâ€Tm are used to send and stop receiving messages respectively
// Received data is stored in ‘buf_rxâ€Tm array and data to be transmitted is stored in ‘buf_txâ€Tm array on CM core of F2838x device
// Examples is Interrupt based with a callback function ‘udp_rx_callbackâ€Tm which handles the received data from the SocketTest/Packet Sender software.
//
//###########################################################################
// $TI Release: $
// $Release Date: $
// $Copyright:
// Copyright (C) 2022 Texas Instruments Incorporated - http://www.ti.com
//
// Redistribution and use in source and binary forms, with or without 
// modification, are permitted provided that the following conditions 
// are met:
// 
//   Redistributions of source code must retain the above copyright 
//   notice, this list of conditions and the following disclaimer.
// 
//   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.
// 
//   Neither the name of Texas Instruments Incorporated 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 
// OWNER 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 <string.h>

#include "inc/hw_ints.h"
#include "inc/hw_memmap.h"
#include "inc/hw_nvic.h"
#include "inc/hw_types.h"
#include "inc/hw_sysctl.h"
#include "inc/hw_emac.h"

#include "driverlib_cm/ethernet.h"
#include "driverlib_cm/gpio.h"
#include "driverlib_cm/interrupt.h"
#include "driverlib_cm/flash.h"

#include "driverlib_cm/sysctl.h"
#include "driverlib_cm/systick.h"

#include "utils/lwiplib.h"
#include "board_drivers/pinout.h"


#include "lwipopts.h"
#include "ipc.h"

//!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

#include "ipc.h"

//!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

#define PAYLOAD 35

volatile uint32_t msTime=0;


volatile bool flag_TX_frame_UDP=true;


#define MAKE_IP_ADDRESS(a0,a1,a2,a3) (((a0<<24) & 0xFF000000) | ((a1<<16) & 0x00FF0000) | ((a2<<8)  & 0x0000FF00) | (a3 & 0x000000FF) )

bool Connected_udp_28000 = false;

uint16_t cnt_Connected_udp_28000 = 0;
uint8_t ISR;
uint8_t VAl;
//uint16_t buf_rx;

// Defines
//
#define PACKET_LENGTH 132

struct udp_pcb *g_upcb;

u8_t buf_rx[PAYLOAD];
u8_t buf_tx[PAYLOAD];
char * buf_tx_start_msg = "Something to show UDP is working \n";
uint32_t buf_tx_start_msg_count = 35;

uint16_t cont_rx_udp = 0;

struct pbuf *pbuf1_tx;


//*****************************************************************************
//
//! \addtogroup master_example_list
//! <h1>Ethernet with lwIP (enet_lwip)</h1>
//!
//! This example application demonstrates the operation of the F2838x
//! microcontroller Ethernet controller using the lwIP TCP/IP Stack. Once
//! programmed, the device sits endlessly waiting for ICMP ping requests. It
//! has a static IP address. To ping the device, the sender has to be in the
//! same network. The stack also supports ARP.
//!
//! For additional details on lwIP, refer to the lwIP web page at:
//! savannah.nongnu.org/.../
//
//*****************************************************************************

// These are defined by the linker (see device linker command file)
extern uint16_t RamfuncsLoadStart;
extern uint16_t RamfuncsLoadSize;
extern uint16_t RamfuncsRunStart;
extern uint16_t RamfuncsLoadEnd;
extern uint16_t RamfuncsRunEnd;
extern uint16_t RamfuncsRunSize;

extern uint16_t constLoadStart;
extern uint16_t constLoadEnd;
extern uint16_t constLoadSize;
extern uint16_t constRunStart;
extern uint16_t constRunEnd;
extern uint16_t constRunSize;

#define DEVICE_FLASH_WAITSTATES 2

//*****************************************************************************
//
// Driver specific initialization code and macro.
//
//*****************************************************************************

#define ETHERNET_NO_OF_RX_PACKETS   2U
#define ETHERNET_MAX_PACKET_LENGTH 1538U

#define NUM_PACKET_DESC_RX_APPLICATION PBUF_POOL_SIZE //8 - same as PBUF_POOL_SIZE

//!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

#define IPC_CMD_READ_MEM   0x1001
#define IPC_CMD_RESP       0x2001

#define TEST_PASS          0x5555
#define TEST_FAIL          0xAAAA

bool status = false;
uint32_t command,add,data;
uint8_t ipisr;
uint8_t ipif;
uint8_t ips;
uint8_t ipi;

IPC_MessageQueue_t messageQueue;

//!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
Ethernet_Handle emac_handle;
Ethernet_InitConfig *pInitCfg;
uint32_t Ethernet_numRxCallbackCustom = 0;
uint32_t releaseTxCount = 0;
uint32_t genericISRCustomcount = 0;
uint32_t genericISRCustomRBUcount = 0;
uint32_t genericISRCustomROVcount = 0;
uint32_t genericISRCustomRIcount = 0;

uint32_t systickPeriodValue = 125000; //15000000;
Ethernet_Pkt_Desc  pktDescriptorRXCustom[NUM_PACKET_DESC_RX_APPLICATION];
extern uint32_t Ethernet_numGetPacketBufferCallback;
extern Ethernet_Device Ethernet_device_struct;
uint8_t Ethernet_rxBuffer[ETHERNET_NO_OF_RX_PACKETS *
                          ETHERNET_MAX_PACKET_LENGTH];

uint32_t sendPacketFailedCount = 0;

uint8_t mac_custom[6] = {0xA8, 0x63, 0xF2, 0x00, 0x1D, 0x98};

extern Ethernet_Pkt_Desc*
lwIPEthernetIntHandler(Ethernet_Pkt_Desc *pPacket);



//!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

__interrupt void IPC_ISR1()
{
    int i;
    IPC_Message_t TxMsg, RxMsg;
    bool status = false;

    //
    // Read the message from the message queue
    //
    IPC_readMessageFromQueue(IPC_CM_L_CPU1_R, &messageQueue, IPC_ADDR_CORRECTION_ENABLE,
                             &RxMsg, IPC_NONBLOCKING_CALL);

    if(RxMsg.command == IPC_CMD_READ_MEM)
    {
        status = true;

        //
        // Read and compare data
        //
        for(i=0; i<RxMsg.dataw1; i++)
        {
            if((*(uint32_t *)RxMsg.address + i) != i)
                status = false;
        }
    }

    //
    // Send response message
    //
    TxMsg.command = IPC_CMD_RESP;
    TxMsg.address = 0; // Not used
    TxMsg.dataw1  = status ? TEST_PASS : TEST_FAIL;
    TxMsg.dataw2  = RxMsg.dataw2; // Use the message identifier from the received message

    IPC_sendMessageToQueue(IPC_CM_L_CPU1_R, &messageQueue, IPC_ADDR_CORRECTION_DISABLE,
                           &TxMsg, IPC_NONBLOCKING_CALL);

    //
    // Acknowledge the flag
    //
    IPC_ackFlagRtoL(IPC_CM_L_CPU1_R, IPC_FLAG1);
}

//!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!


void CM_init(void)
{
    //
    // Disable the watchdog
    //
    SysCtl_disableWatchdog();

#ifdef _FLASH
    //
    // Copy time critical code and flash setup code to RAM. This includes the
    // following functions: InitFlash();
    //
    // The RamfuncsLoadStart, RamfuncsLoadSize, and RamfuncsRunStart symbols
    // are created by the linker. Refer to the device .cmd file.
    // Html pages are also being copied from flash to ram.
    //
    memcpy(&RamfuncsRunStart, &RamfuncsLoadStart, (size_t)&RamfuncsLoadSize);
    memcpy(&constRunStart, &constLoadStart, (size_t)&constLoadSize);
    //
    // Call Flash Initialization to setup flash waitstates. This function must
    // reside in RAM.
    //
    Flash_initModule(FLASH0CTRL_BASE, FLASH0ECC_BASE, DEVICE_FLASH_WAITSTATES);
#endif

    //
    // Sets the NVIC vector table offset address.
    //
#ifdef _FLASH
    Interrupt_setVectorTableOffset((uint32_t)vectorTableFlash);
#else
    Interrupt_setVectorTableOffset((uint32_t)vectorTableRAM);
#endif

}
//*****************************************************************************
//
// HTTP Webserver related callbacks and definitions.
//
//*****************************************************************************
//
// Currently, this implemented as a pointer to function which is called when
// corresponding query is received by the HTTP webserver daemon. When more
// features are needed to be added, it should be implemented as a separate
// interface.
//
void httpLEDToggle(void);
void(*ledtoggleFuncPtr)(void) = &httpLEDToggle;

//*****************************************************************************
//
// The interrupt handler for the SysTick interrupt.
//
//*****************************************************************************
void
SysTickIntHandler(void)
{
    //
    // Call the lwIP timer handler.
    //
 //   lwIPTimer(systickPeriodValue);
	   lwIPTimer(1);
}

//*****************************************************************************
//
//  This function is a callback function called by the example to
//  get a Packet Buffer. Has to return a ETHERNET_Pkt_Desc Structure.
//  Rewrite this API for custom use case.
//
//*****************************************************************************
Ethernet_Pkt_Desc* Ethernet_getPacketBufferCustom(void)
{
    //
    // Get the next packet descriptor from the descriptor pool
    //
    uint32_t shortIndex = (Ethernet_numGetPacketBufferCallback + 3)
                % NUM_PACKET_DESC_RX_APPLICATION;

    //
    // Increment the book-keeping pointer which acts as a head pointer
    // to the circular array of packet descriptor pool.
    //
    Ethernet_numGetPacketBufferCallback++;

    //
    // Update buffer length information to the newly procured packet
    // descriptor.
    //
    pktDescriptorRXCustom[shortIndex].bufferLength =
                                  ETHERNET_MAX_PACKET_LENGTH;

    //
    // Update the receive buffer address in the packer descriptor.
    //
    pktDescriptorRXCustom[shortIndex].dataBuffer =
                                      &Ethernet_device_struct.rxBuffer [ \
               (ETHERNET_MAX_PACKET_LENGTH*Ethernet_device_struct.rxBuffIndex)];

    //
    // Update the receive buffer pool index.
    //
    Ethernet_device_struct.rxBuffIndex += 1U;
    Ethernet_device_struct.rxBuffIndex  = \
    (Ethernet_device_struct.rxBuffIndex%ETHERNET_NO_OF_RX_PACKETS);

    //
    // Receive buffer is usable from Address 0
    //
    pktDescriptorRXCustom[shortIndex].dataOffset = 0U;

    //
    // Return this new descriptor to the driver.
    //
    return (&(pktDescriptorRXCustom[shortIndex]));
}

//*****************************************************************************
//
//  This is a hook function and called by the driver when it receives a
//  packet. Application is expected to replenish the buffer after consuming it.
//  Has to return a ETHERNET_Pkt_Desc Structure.
//  Rewrite this API for custom use case.
//
//*****************************************************************************
Ethernet_Pkt_Desc* Ethernet_receivePacketCallbackCustom(
        Ethernet_Handle handleApplication,
        Ethernet_Pkt_Desc *pPacket)
{

	Ethernet_Pkt_Desc* temp_eth_pkt;
    //
    // Book-keeping to maintain number of callbacks received.
    //
#ifdef ETHERNET_DEBUG
    Ethernet_numRxCallbackCustom++;
#endif



      Ethernet_disableRxDMAReception(EMAC_BASE,0);


    //
    // This is a placeholder for Application specific handling
    // We are replenishing the buffer received with another buffer
    //
  //  return lwIPEthernetIntHandler(pPacket);

      temp_eth_pkt=lwIPEthernetIntHandler(pPacket);


      Ethernet_enableRxDMAReception(EMAC_BASE,0);

      return temp_eth_pkt;
}

void Ethernet_releaseTxPacketBufferCustom(
        Ethernet_Handle handleApplication,
        Ethernet_Pkt_Desc *pPacket)
{
    //
    // Once the packet is sent, reuse the packet memory to avoid
    // memory leaks. Call this interrupt handler function which will take care
    // of freeing the memory used by the packet descriptor.
    //
    lwIPEthernetIntHandler(pPacket);

    //
    // Increment the book-keeping counter.
    //
#ifdef ETHERNET_DEBUG
    releaseTxCount++;
#endif
}

Ethernet_Pkt_Desc *Ethernet_performPopOnPacketQueueCustom(
            Ethernet_PKT_Queue_T *pktQueuePtr)
{
    Ethernet_Pkt_Desc *pktDescHdrPtr;

    pktDescHdrPtr = pktQueuePtr->head;

    if(0U != pktDescHdrPtr)
    {
        pktQueuePtr->head = pktDescHdrPtr->nextPacketDesc;
        pktQueuePtr->count--;
    }

    return(pktDescHdrPtr);
}
void Ethernet_performPushOnPacketQueueCustom(
        Ethernet_PKT_Queue_T *pktQueuePtr,
        Ethernet_Pkt_Desc *pktDescHdrPtr)
{
    pktDescHdrPtr->nextPacketDesc = 0U;

    if(0U == pktQueuePtr->head)
    {
        //
        // Queue is empty - Initialize it with this one packet
        //
        pktQueuePtr->head = pktDescHdrPtr;
        pktQueuePtr->tail = pktDescHdrPtr;
    }
    else
    {
        //
        // Queue is not empty - Push onto END
        //
        pktQueuePtr->tail->nextPacketDesc = pktDescHdrPtr;
        pktQueuePtr->tail        = pktDescHdrPtr;
    }
    pktQueuePtr->count++;
}
void Ethernet_setMACConfigurationCustom(uint32_t base, uint32_t flags)
{
    HWREG(base + ETHERNET_O_MAC_CONFIGURATION) |= flags;
}
void Ethernet_clearMACConfigurationCustom(uint32_t base, uint32_t flags)
{
    HWREG(base + ETHERNET_O_MAC_CONFIGURATION) &= ~flags;

}

interrupt void Ethernet_genericISRCustom(void)
{
    ISR++;
    genericISRCustomcount++;
    Ethernet_RxChDesc *rxChan;
    Ethernet_TxChDesc *txChan;
    Ethernet_HW_descriptor    *descPtr;
    Ethernet_HW_descriptor    *tailPtr;
    uint16_t i=0;
    Ethernet_clearMACConfigurationCustom(Ethernet_device_struct.baseAddresses.enet_base,ETHERNET_MAC_CONFIGURATION_RE);
    Ethernet_clearMACConfigurationCustom(Ethernet_device_struct.baseAddresses.enet_base,ETHERNET_MAC_CONFIGURATION_TE);
    for(i = 0U;i < Ethernet_device_struct.initConfig.numChannels;i++)
     {
         Ethernet_disableRxDMAReception(
               Ethernet_device_struct.baseAddresses.enet_base,
               i);
     }
    if(((ETHERNET_DMA_CH0_STATUS_AIS |
                         ETHERNET_DMA_CH0_STATUS_RBU) ==
                       (HWREG(Ethernet_device_struct.baseAddresses.enet_base +
                              ETHERNET_O_DMA_CH0_STATUS) &
                              (uint32_t)(ETHERNET_DMA_CH0_STATUS_AIS |
                                         ETHERNET_DMA_CH0_STATUS_RBU))) ||
          (ETHERNET_MTL_Q0_INTERRUPT_CONTROL_STATUS_RXOVFIS) ==
                                   (HWREG(Ethernet_device_struct.baseAddresses.enet_base +
                                          ETHERNET_O_MTL_Q0_INTERRUPT_CONTROL_STATUS) &
                                          (uint32_t)(ETHERNET_MTL_Q0_INTERRUPT_CONTROL_STATUS_RXOVFIS
                                                     )))
      {
          if((ETHERNET_DMA_CH0_STATUS_AIS |
                             ETHERNET_DMA_CH0_STATUS_RBU) ==
                           (HWREG(Ethernet_device_struct.baseAddresses.enet_base +
                                  ETHERNET_O_DMA_CH0_STATUS) &
                                  (uint32_t)(ETHERNET_DMA_CH0_STATUS_AIS |
                                             ETHERNET_DMA_CH0_STATUS_RBU)))
          {
          genericISRCustomRBUcount++;
          }
          if((ETHERNET_MTL_Q0_INTERRUPT_CONTROL_STATUS_RXOVFIS) ==
                  (HWREG(Ethernet_device_struct.baseAddresses.enet_base +
                         ETHERNET_O_MTL_Q0_INTERRUPT_CONTROL_STATUS) &
                         (uint32_t)(ETHERNET_MTL_Q0_INTERRUPT_CONTROL_STATUS_RXOVFIS
                                    )))
          {
              genericISRCustomROVcount++;
              Ethernet_enableMTLInterrupt(Ethernet_device_struct.baseAddresses.enet_base,0,
                                          ETHERNET_MTL_Q0_INTERRUPT_CONTROL_STATUS_RXOVFIS);
          }

        /*
             * Clear the AIS and RBU status bit. These MUST be
             * cleared together!
             */
            Ethernet_clearDMAChannelInterrupt(
                    Ethernet_device_struct.baseAddresses.enet_base,
                    ETHERNET_DMA_CHANNEL_NUM_0,
                    ETHERNET_DMA_CH0_STATUS_AIS |
                    ETHERNET_DMA_CH0_STATUS_RBU);

            /*
           *Recover from Receive Buffer Unavailable (and hung DMA)
         *
         * All descriptor buffers are owned by the application, and
         * in result the DMA cannot transfer incoming frames to the
         * buffers (RBU condition). DMA has also entered suspend
         * mode at this point, too.
         *
         * Drain the RX queues
         */

            /* Upon RBU error, discard all previously received packets */
            if(Ethernet_device_struct.initConfig.pfcbDeletePackets != NULL)
                (*Ethernet_device_struct.initConfig.pfcbDeletePackets)();

            rxChan =
               &Ethernet_device_struct.dmaObj.rxDma[ETHERNET_DMA_CHANNEL_NUM_0];
            txChan=
               &Ethernet_device_struct.dmaObj.txDma[ETHERNET_DMA_CHANNEL_NUM_0];

    /*
     * Need to disable multiple interrupts, so protect the code to do so within
     * a global disable block (to prevent getting interrupted in between)
     */

            if(NULL!= Ethernet_device_struct.ptrPlatformInterruptDisable)
            {
                (*Ethernet_device_struct.ptrPlatformInterruptDisable)(
                    Ethernet_device_struct.interruptNum[
                        ETHERNET_RX_INTR_CH0 + rxChan->chInfo->chNum]);

                (*Ethernet_device_struct.ptrPlatformInterruptDisable)(
                    Ethernet_device_struct.interruptNum[
                        ETHERNET_GENERIC_INTERRUPT]);
            }
            /* verify we have full capacity in the descriptor queue */
            if(rxChan->descQueue.count < rxChan->descMax) {
              /* The queue is not at full capacity due to OOM errors.
              Try to fill it again */
                Ethernet_addPacketsIntoRxQueue(rxChan);
            }
            Ethernet_initRxChannel(
                    &Ethernet_device_struct.initConfig.chInfo[ETHERNET_CH_DIR_RX][0]);

            Ethernet_writeRxDescTailPointer(
                Ethernet_device_struct.baseAddresses.enet_base,
                0,
                (&Ethernet_device_struct.rxDesc[
                 ((uint32_t)ETHERNET_DESCRIPTORS_NUM_RX_PER_CHANNEL) *
                  (0 + (uint32_t)1U)]));

            if(NULL!= Ethernet_device_struct.ptrPlatformInterruptEnable)
            {
                (*Ethernet_device_struct.ptrPlatformInterruptEnable)(
                    Ethernet_device_struct.interruptNum[
                        ETHERNET_RX_INTR_CH0 + rxChan->chInfo->chNum]);
                (*Ethernet_device_struct.ptrPlatformInterruptEnable)(
                    Ethernet_device_struct.interruptNum[
                        ETHERNET_GENERIC_INTERRUPT]);
            }


    }
    if(0U != (HWREG(Ethernet_device_struct.baseAddresses.enet_base +
                                 ETHERNET_O_DMA_CH0_STATUS) &
                           (uint32_t) ETHERNET_DMA_CH0_STATUS_RI))
    {
        genericISRCustomRIcount++;
        Ethernet_clearDMAChannelInterrupt(
                        Ethernet_device_struct.baseAddresses.enet_base,
                        ETHERNET_DMA_CHANNEL_NUM_0,
                        ETHERNET_DMA_CH0_STATUS_NIS | ETHERNET_DMA_CH0_STATUS_RI);
    }

    for(i = 0U;i < Ethernet_device_struct.initConfig.numChannels;i++)
     {
         Ethernet_enableRxDMAReception(
               Ethernet_device_struct.baseAddresses.enet_base,
               i);
     }
    Ethernet_setMACConfigurationCustom(Ethernet_device_struct.baseAddresses.enet_base,ETHERNET_MAC_CONFIGURATION_RE);
    Ethernet_setMACConfigurationCustom(Ethernet_device_struct.baseAddresses.enet_base,ETHERNET_MAC_CONFIGURATION_TE);
}

void
Ethernet_init(const unsigned char *mac)
{
    Ethernet_InitInterfaceConfig initInterfaceConfig;
    uint32_t macLower;
    uint32_t macHigher;
    uint8_t *temp;

    initInterfaceConfig.ssbase = EMAC_SS_BASE;
    initInterfaceConfig.enet_base = EMAC_BASE;
    initInterfaceConfig.phyMode = ETHERNET_SS_PHY_INTF_SEL_MII;

    //
    // Assign SoC specific functions for Enabling,Disabling interrupts
    // and for enabling the Peripheral at system level
    //
    initInterfaceConfig.ptrPlatformInterruptDisable =
                                                    &Platform_disableInterrupt;
    initInterfaceConfig.ptrPlatformInterruptEnable =
                                                     &Platform_enableInterrupt;
    initInterfaceConfig.ptrPlatformPeripheralEnable =
                                                    &Platform_enablePeripheral;
    initInterfaceConfig.ptrPlatformPeripheralReset =
                                                     &Platform_resetPeripheral;

    //
    // Assign the peripheral number at the SoC
    //
    initInterfaceConfig.peripheralNum = SYSCTL_PERIPH_CLK_ENET;

    //
    // Assign the default SoC specific interrupt numbers of Ethernet interrupts
    //
    initInterfaceConfig.interruptNum[0] = INT_EMAC;
    initInterfaceConfig.interruptNum[1] = INT_EMAC_TX0;
    initInterfaceConfig.interruptNum[2] = INT_EMAC_TX1;
    initInterfaceConfig.interruptNum[3] = INT_EMAC_RX0;
    initInterfaceConfig.interruptNum[4] = INT_EMAC_RX1;

    pInitCfg = Ethernet_initInterface(initInterfaceConfig);

    Ethernet_getInitConfig(pInitCfg);

    pInitCfg->dmaMode.InterruptMode = ETHERNET_DMA_MODE_INTM_MODE2;

    //
    // Assign the callbacks for Getting packet buffer when needed
    // Releasing the TxPacketBuffer on Transmit interrupt callbacks
    // Receive packet callback on Receive packet completion interrupt
    //
    pInitCfg->pfcbRxPacket = &Ethernet_receivePacketCallbackCustom;
    pInitCfg->pfcbGetPacket = &Ethernet_getPacketBuffer;    //custom
    pInitCfg->pfcbFreePacket = &Ethernet_releaseTxPacketBufferCustom;

    //
    //Assign the Buffer to be used by the Low level driver for receiving
    //Packets. This should be accessible by the Ethernet DMA
    //
    pInitCfg->rxBuffer = Ethernet_rxBuffer;

    //
    // The Application handle is not used by this application
    // Hence using a dummy value of 1
    //
    Ethernet_getHandle((Ethernet_Handle)1, pInitCfg , &emac_handle);

    //
    // Disable transmit buffer unavailable and normal interrupt which
    // are enabled by default in Ethernet_getHandle.
    //
    Ethernet_disableDmaInterrupt(Ethernet_device_struct.baseAddresses.enet_base,
                                 0, (ETHERNET_DMA_CH0_INTERRUPT_ENABLE_TBUE |
                                     ETHERNET_DMA_CH0_INTERRUPT_ENABLE_NIE));

    //
    // Enable the MTL interrupt to service the receive FIFO overflow
    // condition in the Ethernet module.
    //
    Ethernet_enableMTLInterrupt(Ethernet_device_struct.baseAddresses.enet_base,0,
                                ETHERNET_MTL_Q0_INTERRUPT_CONTROL_STATUS_RXOIE);

    //
    // Disable the MAC Management counter interrupts as they are not used
    // in this application.
    //
    HWREG(Ethernet_device_struct.baseAddresses.enet_base + ETHERNET_O_MMC_RX_INTERRUPT_MASK) = 0xFFFFFFFF;
    HWREG(Ethernet_device_struct.baseAddresses.enet_base + ETHERNET_O_MMC_IPC_RX_INTERRUPT_MASK) = 0xFFFFFFFF;
    //
    //Do global Interrupt Enable
    //
    (void)Interrupt_enableInProcessor();

    //
    //Assign default ISRs
    //
    Interrupt_registerHandler(INT_EMAC_TX0, Ethernet_transmitISR);
    Interrupt_registerHandler(INT_EMAC_RX0, Ethernet_receiveISR);
    Interrupt_registerHandler(INT_EMAC, Ethernet_genericISRCustom);

    //
    // Convert the mac address string into the 32/16 split variables format
    // that is required by the driver to program into hardware registers.
    // Note: This step is done after the Ethernet_getHandle function because
    //       a dummy MAC address is programmed in that function.
    //
    temp = (uint8_t *)&macLower;
    temp[0] = mac[0];
    temp[1] = mac[1];
    temp[2] = mac[2];
    temp[3] = mac[3];

    temp = (uint8_t *)&macHigher;
    temp[0] = mac[4];
    temp[1] = mac[5];

    //
    // Program the unicast mac address.
    //
    Ethernet_setMACAddr(EMAC_BASE,
                        0,
                        macHigher,
                        macLower,
                        ETHERNET_CHANNEL_0);

    Ethernet_clearMACConfigurationCustom(Ethernet_device_struct.baseAddresses.enet_base,ETHERNET_MAC_CONFIGURATION_RE);
    Ethernet_setMACConfigurationCustom(Ethernet_device_struct.baseAddresses.enet_base,ETHERNET_MAC_CONFIGURATION_RE);
}




void udp_rx_callback(void *arg, struct udp_pcb *upcb, struct pbuf *p,
               struct ip_addr *addr, u16_t port)

{
    char *cad_rx;
    uint16_t long_actual = 0;
    uint16_t long_UDP_complete = 0;
    uint16_t long_total = 0;
    uint8_t cnt_lee = 0;

    httpLEDToggle();


    memset(buf_rx, 0x00, 50);


    long_total = p->tot_len;

    cont_rx_udp++;



    while ((long_UDP_complete < long_total)
            && (long_UDP_complete < 1800) || (cnt_lee == 0))
    {
        cnt_lee++;
        long_actual = p->len;

        cad_rx = p->payload;

        int i = 0;
        for (i = 0; i < long_actual; i++)
        {

            buf_rx[0 + i + long_UDP_complete] = *cad_rx++;
        }
        long_UDP_complete = long_actual + long_UDP_complete;
        buf_rx[long_UDP_complete + 1] = '\n';

        if (long_UDP_complete == long_total)
        {
            pbuf_free(p); //* don't leak the pbuf!
        }
        else
        {
            if ( p->next != NULL)
            p = p->next;
            //  pbuf_free(a);                                   /* don't leak the pbuf!*/
        }

        if ((buf_rx[0] == 'S') && (buf_rx[1] == 'T') && (buf_rx[2] == 'O') && (buf_rx[3] == 'P'))
        {                    //Disconnect
                             //udp_disconnect(upcb);

            Connected_udp_28000 = false;
            cnt_Connected_udp_28000 = 0;
        }

        else if ((buf_rx[0] == 'S') && (buf_rx[1] == 'T') && (buf_rx[2] == 'A') && (buf_rx[3] == 'R') && (buf_rx[4] == 'T'))
        {                //Connect

                    Connected_udp_28000 = true;
                    cnt_Connected_udp_28000 = 0;

                   /* process the payload in p->payload */
                   udp_connect(upcb, addr, port); /* connect to the remote host */

        }
    }

    pbuf_free(p);

    if (!Connected_udp_28000)
    {
        udp_disconnect(upcb);
    }

}

/* UDP initialization ......................................................*/
void my_udp_init(void)
{

    g_upcb = udp_new();
    udp_bind(g_upcb, IP_ADDR_ANY, 28000);
    udp_recv(g_upcb, &udp_rx_callback, (void*) 0);


}


//*****************************************************************************
//
// This example demonstrates the use of the Ethernet Controller.
//
//*****************************************************************************

//unsigned long IPAddr =  0xC0A80004; // 0xC0A80004; //192.168.0.4
unsigned long IPAddr = 0xC300004D;
unsigned long NetMask = 0xFFFFFF00;
unsigned long GWAddr = 0x00000000;


int
main(void)
{
    unsigned long ulUser0, ulUser1;
    unsigned char pucMACArray[8];
    int i=0;


    //  ////////////////////////////////////////
    // Initializing the CM. Loading the required functions to SRAM.
    //
    CM_init();

    SYSTICK_setPeriod(systickPeriodValue);
    SYSTICK_enableCounter();
    SYSTICK_registerInterruptHandler(SysTickIntHandler);
    SYSTICK_enableInterrupt();

    //
    // Enable processor interrupts.
    //
    Interrupt_enableInProcessor();

    // Set user/company specific MAC octets
    // (for this code we are using A8-63-F2-00-00-80)
    // 0x00 MACOCT3 MACOCT2 MACOCT1
    ulUser0 = 0x00F263A8;

    // 0x00 MACOCT6 MACOCT5 MACOCT4
    ulUser1 = 0x00800000;

    //
    // Convert the 24/24 split MAC address from NV ram into a 32/16 split MAC
    // address needed to program the hardware registers, then program the MAC
    // address into the Ethernet Controller registers.
    //
    pucMACArray[0] = ((ulUser0 >>  0) & 0xff);
    pucMACArray[1] = ((ulUser0 >>  8) & 0xff);
    pucMACArray[2] = ((ulUser0 >> 16) & 0xff);
    pucMACArray[3] = ((ulUser1 >>  0) & 0xff);
    pucMACArray[4] = ((ulUser1 >>  8) & 0xff);
    pucMACArray[5] = ((ulUser1 >> 16) & 0xff);

    //
    // Initialize ethernet module.
    //
    Ethernet_init(pucMACArray);

    //
    // Initialze the lwIP library, using DHCP.
    //
    lwIPInit(0, pucMACArray, IPAddr, NetMask, GWAddr, IPADDR_USE_STATIC);

    // Initialize the UDP server
    //
    my_udp_init();


    //
    // Loop forever. All the work is done in interrupt handlers.
    //
     uint32_t cnt_FFT = 0;

    Interrupt_setPriority(INT_EMAC_TX0, 2);
    Interrupt_setPriority(INT_EMAC_RX0, 1);
    Interrupt_enable(INT_EMAC_TX0);
    Interrupt_enable(INT_EMAC_RX0);
    Interrupt_enable(INT_EMAC);

    volatile int cnt_total_loop=0;
    volatile int cnt_total_mqtt_pub=0;

    while (1)
    {


        cnt_total_loop++;

        if (Connected_udp_28000)
        {
        	//UDP TX block

            if (flag_TX_frame_UDP)
            {
            	cnt_FFT++;

            	flag_TX_frame_UDP = false;
            	/*
            	/////////////////////////////////////////////
            	for (i = 0; i < PAYLOAD; i++)
                {
            	    if(i < buf_tx_start_msg_count)
            	    {
            	        buf_tx[i] = (uint8_t)buf_tx_start_msg[i];
            	    }
            	    else
            	    {
                        buf_tx[i] = (uint8_t) (cnt_FFT);
            	    }

                }
         */
            	////////////////////////////////////////////

                pbuf1_tx = pbuf_alloc(PBUF_TRANSPORT, PAYLOAD, PBUF_RAM);
                if (pbuf1_tx!= NULL)
                {
                pbuf1_tx->payload = (void*) buf_tx ;
                pbuf1_tx->tot_len = PAYLOAD;  //17        // long_UDP_complete+4;
                pbuf1_tx->len = PAYLOAD;   //17       // long_UDP_complete+4;

                	udp_send(g_upcb, pbuf1_tx);

                }


                cnt_Connected_udp_28000++;


                if (pbuf1_tx!= NULL)
                pbuf_free(pbuf1_tx);

            }

        }


        SysCtl_delay(6000000);//aprox 1 sec

        sys_check_timeouts();
//!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

            IPC_clearFlagLtoR(IPC_CM_L_CPU1_R, IPC_FLAG_ALL);

            //
            // Enable IPC interrupts
            //
            IPC_registerInterrupt(IPC_CM_L_CPU1_R, IPC_INT0, IPC_ISR0);

            //
            // Synchronize both the cores.
            //

            IPC_sync(IPC_CM_L_CPU1_R, IPC_FLAG31);

            //
            // Loop forever. Wait for IPC interrupt
            //

//!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

    }
//!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
   // while(1);
//!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
}
//*****************************************************************************
//
// Called by lwIP Library. Toggles the led when a command is received by the
// HTTP webserver.
//
//*****************************************************************************
void httpLEDToggle(void)
{
    //
    // Toggle the LED D1 on the control card.
    //
    GPIO_togglePin(DEVICE_GPIO_PIN_LED1);
}


//*****************************************************************************
//
// Called by lwIP Library. Could be used for periodic custom tasks.
//
//*****************************************************************************

uint32_t cnt_ms_lwip_Htimer=0;
uint32_t cnt_ms_TX_Htimer=0;
void lwIPHostTimerHandler(void)
{
//	msTime++;

	cnt_ms_lwip_Htimer++;
}

  • 请注意,本文内容源自机器翻译,可能存在语法或其它翻译错误,仅供参考。如需获取准确内容,请参阅链接中的英语原文或自行翻译。

    您好、Rahul、

    请提供您尝试完成的工作以及您在论坛中遇到的问题的背景信息。  只是附加您的代码并不会有所帮助。  我们的带宽非常有限、无法对您的代码进行审计、也无法准确指出问题所在。  向我们提供一些细节有望缩小问题的范围。

    谢谢、

    Joseph