apply auto-formatter

This commit is contained in:
2022-05-05 20:55:28 +02:00
parent c2a9db8ac8
commit c88a534e1c
42 changed files with 1667 additions and 1859 deletions

View File

@ -1,33 +1,33 @@
#include "STM32TestTask.h"
#include "stm32h7xx_nucleo.h"
#include "OBSWConfig.h"
STM32TestTask::STM32TestTask(object_id_t objectId, bool enablePrintout,
bool blinkyLed): TestTask(objectId), blinkyLed(blinkyLed) {
BSP_LED_Init(LED1);
BSP_LED_Init(LED2);
BSP_LED_Init(LED3);
#include "OBSWConfig.h"
#include "stm32h7xx_nucleo.h"
STM32TestTask::STM32TestTask(object_id_t objectId, bool enablePrintout, bool blinkyLed)
: TestTask(objectId), blinkyLed(blinkyLed) {
BSP_LED_Init(LED1);
BSP_LED_Init(LED2);
BSP_LED_Init(LED3);
}
ReturnValue_t STM32TestTask::performPeriodicAction() {
if(blinkyLed) {
if (blinkyLed) {
#if OBSW_ETHERNET_USE_LEDS == 0
BSP_LED_Toggle(LED1);
BSP_LED_Toggle(LED2);
BSP_LED_Toggle(LED1);
BSP_LED_Toggle(LED2);
#endif
BSP_LED_Toggle(LED3);
}
if(testSpi) {
spiTest->performOperation();
}
return TestTask::performPeriodicAction();
BSP_LED_Toggle(LED3);
}
if (testSpi) {
spiTest->performOperation();
}
return TestTask::performPeriodicAction();
}
ReturnValue_t STM32TestTask::initialize() {
if(testSpi) {
spiComIF = new SpiComIF(objects::SPI_COM_IF);
spiTest = new SpiTest(*spiComIF);
}
return TestTask::initialize();
if (testSpi) {
spiComIF = new SpiComIF(objects::SPI_COM_IF);
spiTest = new SpiTest(*spiComIF);
}
return TestTask::initialize();
}

View File

@ -4,22 +4,19 @@
#include "bsp_stm32h7_freertos/boardtest/SpiTest.h"
#include "fsfw_tests/integration/task/TestTask.h"
class STM32TestTask: public TestTask {
public:
STM32TestTask(object_id_t objectId, bool enablePrintout, bool blinkyLed = true);
class STM32TestTask : public TestTask {
public:
STM32TestTask(object_id_t objectId, bool enablePrintout, bool blinkyLed = true);
ReturnValue_t initialize() override;
ReturnValue_t performPeriodicAction() override;
private:
ReturnValue_t initialize() override;
ReturnValue_t performPeriodicAction() override;
SpiComIF* spiComIF = nullptr;
SpiTest* spiTest = nullptr;
bool blinkyLed = false;
bool testSpi = true;
private:
SpiComIF* spiComIF = nullptr;
SpiTest* spiTest = nullptr;
bool blinkyLed = false;
bool testSpi = true;
};
#endif /* BSP_STM32_BOARDTEST_STM32TESTTASK_H_ */

View File

@ -1,204 +1,189 @@
#include "TmTcLwIpUdpBridge.h"
#include "udp_config.h"
#include <OBSWConfig.h>
#include <fsfw/ipc/MutexGuard.h>
#include <fsfw/serialize/EndianConverter.h>
#include <fsfw/serviceinterface/ServiceInterface.h>
#include "app_ethernet.h"
#include "ethernetif.h"
#include <OBSWConfig.h>
#include "udp_config.h"
#include <fsfw/ipc/MutexGuard.h>
#include <fsfw/serviceinterface/ServiceInterface.h>
#include <fsfw/serialize/EndianConverter.h>
TmTcLwIpUdpBridge::TmTcLwIpUdpBridge(object_id_t objectId,
object_id_t ccsdsPacketDistributor, object_id_t tmStoreId,
object_id_t tcStoreId):
TmTcBridge(objectId, ccsdsPacketDistributor, tmStoreId, tcStoreId) {
TmTcLwIpUdpBridge::lastAdd.addr = IPADDR_TYPE_ANY;
TmTcLwIpUdpBridge::TmTcLwIpUdpBridge(object_id_t objectId, object_id_t ccsdsPacketDistributor,
object_id_t tmStoreId, object_id_t tcStoreId)
: TmTcBridge(objectId, ccsdsPacketDistributor, tmStoreId, tcStoreId) {
TmTcLwIpUdpBridge::lastAdd.addr = IPADDR_TYPE_ANY;
}
TmTcLwIpUdpBridge::~TmTcLwIpUdpBridge() {}
ReturnValue_t TmTcLwIpUdpBridge::initialize() {
TmTcBridge::initialize();
bridgeLock = MutexFactory::instance()->createMutex();
if(bridgeLock == nullptr) {
return ObjectManagerIF::CHILD_INIT_FAILED;
}
ReturnValue_t result = udp_server_init();
return result;
TmTcBridge::initialize();
bridgeLock = MutexFactory::instance()->createMutex();
if (bridgeLock == nullptr) {
return ObjectManagerIF::CHILD_INIT_FAILED;
}
ReturnValue_t result = udp_server_init();
return result;
}
ReturnValue_t TmTcLwIpUdpBridge::udp_server_init(void) {
err_t err;
/* Create a new UDP control block */
TmTcLwIpUdpBridge::upcb = udp_new();
if (TmTcLwIpUdpBridge::upcb)
{
/* Bind the upcb to the UDP_PORT port */
/* Using IP_ADDR_ANY allow the upcb to be used by any local interface */
err = udp_bind(TmTcLwIpUdpBridge::upcb, IP_ADDR_ANY, UDP_SERVER_PORT);
err_t err;
/* Create a new UDP control block */
TmTcLwIpUdpBridge::upcb = udp_new();
if (TmTcLwIpUdpBridge::upcb) {
/* Bind the upcb to the UDP_PORT port */
/* Using IP_ADDR_ANY allow the upcb to be used by any local interface */
err = udp_bind(TmTcLwIpUdpBridge::upcb, IP_ADDR_ANY, UDP_SERVER_PORT);
if(err == ERR_OK)
{
/* Set a receive callback for the upcb */
udp_recv(TmTcLwIpUdpBridge::upcb, &udp_server_receive_callback,
(void*) this);
return RETURN_OK;
}
else
{
udp_remove(TmTcLwIpUdpBridge::upcb);
return RETURN_FAILED;
}
if (err == ERR_OK) {
/* Set a receive callback for the upcb */
udp_recv(TmTcLwIpUdpBridge::upcb, &udp_server_receive_callback, (void*)this);
return RETURN_OK;
} else {
return RETURN_FAILED;
udp_remove(TmTcLwIpUdpBridge::upcb);
return RETURN_FAILED;
}
} else {
return RETURN_FAILED;
}
}
ReturnValue_t TmTcLwIpUdpBridge::performOperation(uint8_t operationCode) {
TmTcBridge::performOperation();
TmTcBridge::performOperation();
#if TCPIP_RECV_WIRETAPPING == 1
if(connectFlag) {
uint32_t ipAddress = ((ip4_addr*) &lastAdd)->addr;
int ipAddress1 = (ipAddress & 0xFF000000) >> 24;
int ipAddress2 = (ipAddress & 0xFF0000) >> 16;
int ipAddress3 = (ipAddress & 0xFF00) >> 8;
int ipAddress4 = ipAddress & 0xFF;
if (connectFlag) {
uint32_t ipAddress = ((ip4_addr*)&lastAdd)->addr;
int ipAddress1 = (ipAddress & 0xFF000000) >> 24;
int ipAddress2 = (ipAddress & 0xFF0000) >> 16;
int ipAddress3 = (ipAddress & 0xFF00) >> 8;
int ipAddress4 = ipAddress & 0xFF;
#if OBSW_VERBOSE_LEVEL == 1
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::info << "TmTcLwIpUdpBridge: Client IP Address " << std::dec
<< ipAddress4 << "." << ipAddress3 << "." << ipAddress2 << "."
<< ipAddress1 << std::endl;
uint16_t portSwapped = EndianConverter::convertBigEndian(lastPort);
sif::info << "TmTcLwIpUdpBridge: Client IP Port "
<< (int)portSwapped << std::endl;
sif::info << "TmTcLwIpUdpBridge: Client IP Address " << std::dec << ipAddress4 << "."
<< ipAddress3 << "." << ipAddress2 << "." << ipAddress1 << std::endl;
uint16_t portSwapped = EndianConverter::convertBigEndian(lastPort);
sif::info << "TmTcLwIpUdpBridge: Client IP Port " << (int)portSwapped << std::endl;
#else
sif::printInfo("TmTcLwIpUdpBridge: Client IP Address %d.%d.%d.%d\n",
ipAddress4, ipAddress3, ipAddress2, ipAddress1);
uint16_t portSwapped = EndianConverter::convertBigEndian(lastPort);
sif::printInfo("TmTcLwIpUdpBridge: Client IP Port: %d\n", portSwapped);
sif::printInfo("TmTcLwIpUdpBridge: Client IP Address %d.%d.%d.%d\n", ipAddress4, ipAddress3,
ipAddress2, ipAddress1);
uint16_t portSwapped = EndianConverter::convertBigEndian(lastPort);
sif::printInfo("TmTcLwIpUdpBridge: Client IP Port: %d\n", portSwapped);
#endif
#endif
connectFlag = false;
}
connectFlag = false;
}
#endif
return RETURN_OK;
return RETURN_OK;
}
ReturnValue_t TmTcLwIpUdpBridge::sendTm(const uint8_t * data, size_t dataLen) {
struct pbuf *p_tx = pbuf_alloc(PBUF_TRANSPORT, dataLen, PBUF_RAM);
if ((p_tx != nullptr) && (lastAdd.addr != IPADDR_TYPE_ANY) && (upcb != nullptr)) {
/* copy data to pbuf */
err_t err = pbuf_take(p_tx, (char*) data, dataLen);
if(err!=ERR_OK){
pbuf_free(p_tx);
return err;
}
/* Connect to the remote client */
err = udp_connect(TmTcLwIpUdpBridge::upcb, &lastAdd , lastPort);
if(err != ERR_OK){
pbuf_free(p_tx);
return err;
}
/* Tell the client that we have accepted it */
err = udp_send(TmTcLwIpUdpBridge::upcb, p_tx);
pbuf_free(p_tx);
if(err!=ERR_OK){
return err;
}
/* free the UDP connection, so we can accept new clients */
udp_disconnect (TmTcLwIpUdpBridge::upcb);
ReturnValue_t TmTcLwIpUdpBridge::sendTm(const uint8_t* data, size_t dataLen) {
struct pbuf* p_tx = pbuf_alloc(PBUF_TRANSPORT, dataLen, PBUF_RAM);
if ((p_tx != nullptr) && (lastAdd.addr != IPADDR_TYPE_ANY) && (upcb != nullptr)) {
/* copy data to pbuf */
err_t err = pbuf_take(p_tx, (char*)data, dataLen);
if (err != ERR_OK) {
pbuf_free(p_tx);
return err;
}
else{
return RETURN_FAILED;
/* Connect to the remote client */
err = udp_connect(TmTcLwIpUdpBridge::upcb, &lastAdd, lastPort);
if (err != ERR_OK) {
pbuf_free(p_tx);
return err;
}
return RETURN_OK;
}
void TmTcLwIpUdpBridge::udp_server_receive_callback(void* arg,
struct udp_pcb* upcb_, struct pbuf* p, const ip_addr_t* addr,
u16_t port) {
struct pbuf *p_tx = nullptr;
auto udpBridge = reinterpret_cast<TmTcLwIpUdpBridge*>(arg);
if(udpBridge == nullptr) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "TmTcLwIpUdpBridge::udp_server_receive_callback: Invalid UDP bridge!" <<
std::endl;
#else
sif::printWarning("TmTcLwIpUdpBridge::udp_server_receive_callback: Invalid UDP bridge!\n");
#endif
}
/* allocate pbuf from RAM*/
p_tx = pbuf_alloc(PBUF_TRANSPORT,p->len, PBUF_RAM);
if(p_tx != NULL)
{
if(udpBridge != nullptr) {
MutexGuard lg(udpBridge->bridgeLock);
udpBridge->upcb = upcb_;
udpBridge->lastAdd = *addr;
udpBridge->lastPort = port;
if(not udpBridge->comLinkUp()) {
udpBridge->registerCommConnect();
#if TCPIP_RECV_WIRETAPPING == 1
udpBridge->connectFlag = true;
#endif
/* This should have already been done, but we will still do it */
udpBridge->physicalConnectStatusChange(true);
}
}
pbuf_take(p_tx, (char*)p->payload, p->len);
/* send the received data to the uart port */
char* data = reinterpret_cast<char*>(p_tx->payload);
*(data+p_tx->len) = '\0';
#if TCPIP_RECV_WIRETAPPING == 1
udpBridge->printData(p,data);
#endif
store_address_t storeId;
ReturnValue_t returnValue = udpBridge->tcStore->addData(&storeId,
reinterpret_cast<uint8_t*>(p->payload), p->len);
if (returnValue != RETURN_OK) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "UDP Server: Data storage failed" << std::endl;
#endif
pbuf_free(p_tx);
return;
}
TmTcMessage message(storeId);
if (udpBridge->tmTcReceptionQueue->sendToDefault(&message)
!= RETURN_OK) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "TmTcLwIpUdpBridgw::udp_server_receive_callback:"
<< " Sending message to queue failed" << std::endl;
#endif
udpBridge->tcStore->deleteData(storeId);
}
}
/* Free the p_tx buffer */
/* Tell the client that we have accepted it */
err = udp_send(TmTcLwIpUdpBridge::upcb, p_tx);
pbuf_free(p_tx);
if (err != ERR_OK) {
return err;
}
/* free the UDP connection, so we can accept new clients */
udp_disconnect(TmTcLwIpUdpBridge::upcb);
} else {
return RETURN_FAILED;
}
return RETURN_OK;
}
void TmTcLwIpUdpBridge::udp_server_receive_callback(void* arg, struct udp_pcb* upcb_,
struct pbuf* p, const ip_addr_t* addr,
u16_t port) {
struct pbuf* p_tx = nullptr;
auto udpBridge = reinterpret_cast<TmTcLwIpUdpBridge*>(arg);
if (udpBridge == nullptr) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "TmTcLwIpUdpBridge::udp_server_receive_callback: Invalid UDP bridge!"
<< std::endl;
#else
sif::printWarning("TmTcLwIpUdpBridge::udp_server_receive_callback: Invalid UDP bridge!\n");
#endif
}
/* allocate pbuf from RAM*/
p_tx = pbuf_alloc(PBUF_TRANSPORT, p->len, PBUF_RAM);
if (p_tx != NULL) {
if (udpBridge != nullptr) {
MutexGuard lg(udpBridge->bridgeLock);
udpBridge->upcb = upcb_;
udpBridge->lastAdd = *addr;
udpBridge->lastPort = port;
if (not udpBridge->comLinkUp()) {
udpBridge->registerCommConnect();
#if TCPIP_RECV_WIRETAPPING == 1
udpBridge->connectFlag = true;
#endif
/* This should have already been done, but we will still do it */
udpBridge->physicalConnectStatusChange(true);
}
}
pbuf_take(p_tx, (char*)p->payload, p->len);
/* send the received data to the uart port */
char* data = reinterpret_cast<char*>(p_tx->payload);
*(data + p_tx->len) = '\0';
#if TCPIP_RECV_WIRETAPPING == 1
udpBridge->printData(p, data);
#endif
store_address_t storeId;
ReturnValue_t returnValue =
udpBridge->tcStore->addData(&storeId, reinterpret_cast<uint8_t*>(p->payload), p->len);
if (returnValue != RETURN_OK) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "UDP Server: Data storage failed" << std::endl;
#endif
pbuf_free(p_tx);
return;
}
TmTcMessage message(storeId);
if (udpBridge->tmTcReceptionQueue->sendToDefault(&message) != RETURN_OK) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "TmTcLwIpUdpBridgw::udp_server_receive_callback:"
<< " Sending message to queue failed" << std::endl;
#endif
udpBridge->tcStore->deleteData(storeId);
}
}
/* Free the p_tx buffer */
pbuf_free(p_tx);
}
/* Caller must ensure thread-safety */
bool TmTcLwIpUdpBridge::comLinkUp() const {
return communicationLinkUp;
}
bool TmTcLwIpUdpBridge::comLinkUp() const { return communicationLinkUp; }
/* Caller must ensure thread-safety */
void TmTcLwIpUdpBridge::physicalConnectStatusChange(bool connect) {
if(connect) {
/* Physical connection does not mean there is a recipient to send packets too.
This will be done by the receive callback! */
physicalConnection = true;
}
else {
physicalConnection = false;
/* If there is no physical connection, we can't send anything back */
registerCommDisconnect();
}
if (connect) {
/* Physical connection does not mean there is a recipient to send packets too.
This will be done by the receive callback! */
physicalConnection = true;
} else {
physicalConnection = false;
/* If there is no physical connection, we can't send anything back */
registerCommDisconnect();
}
}

View File

@ -2,9 +2,8 @@
#define BSP_STM32_RTEMS_NETWORKING_TMTCUDPBRIDGE_H_
#include <fsfw/tmtcservices/TmTcBridge.h>
#include <lwip/udp.h>
#include <lwip/ip_addr.h>
#include <lwip/udp.h>
#define TCPIP_RECV_WIRETAPPING 0
@ -12,68 +11,67 @@
* This bridge is used to forward TMTC packets received via LwIP UDP to the internal software bus.
*/
class TmTcLwIpUdpBridge : public TmTcBridge {
friend class UdpTcLwIpPollingTask;
public:
TmTcLwIpUdpBridge(object_id_t objectId,
object_id_t ccsdsPacketDistributor, object_id_t tmStoreId,
object_id_t tcStoreId);
virtual ~TmTcLwIpUdpBridge();
friend class UdpTcLwIpPollingTask;
virtual ReturnValue_t initialize() override;
ReturnValue_t udp_server_init();
public:
TmTcLwIpUdpBridge(object_id_t objectId, object_id_t ccsdsPacketDistributor, object_id_t tmStoreId,
object_id_t tcStoreId);
virtual ~TmTcLwIpUdpBridge();
/**
* In addition to default implementation, ethernet link status is checked.
* @param operationCode
* @return
*/
virtual ReturnValue_t performOperation(uint8_t operationCode = 0) override;
virtual ReturnValue_t initialize() override;
ReturnValue_t udp_server_init();
/** TM Send implementation uses udp_send function from lwIP stack
* @param data
* @param dataLen
* @return
*/
virtual ReturnValue_t sendTm(const uint8_t * data, size_t dataLen) override;
/**
* In addition to default implementation, ethernet link status is checked.
* @param operationCode
* @return
*/
virtual ReturnValue_t performOperation(uint8_t operationCode = 0) override;
/**
* @brief This function is called when an UDP datagram has been
* received on the port UDP_PORT.
* @param arg
* @param upcb_
* @param p
* @param addr Source address which will be bound to TmTcUdpBridge::lastAdd
* @param port
*/
static void udp_server_receive_callback(void *arg,
struct udp_pcb *upcb_, struct pbuf *p, const ip_addr_t *addr,
u16_t port);
/** TM Send implementation uses udp_send function from lwIP stack
* @param data
* @param dataLen
* @return
*/
virtual ReturnValue_t sendTm(const uint8_t *data, size_t dataLen) override;
/**
* Check whether the communication link is up.
* Caller must ensure thread-safety by using the bridge lock.
* @return
*/
bool comLinkUp() const;
/**
* @brief This function is called when an UDP datagram has been
* received on the port UDP_PORT.
* @param arg
* @param upcb_
* @param p
* @param addr Source address which will be bound to TmTcUdpBridge::lastAdd
* @param port
*/
static void udp_server_receive_callback(void *arg, struct udp_pcb *upcb_, struct pbuf *p,
const ip_addr_t *addr, u16_t port);
private:
struct udp_pcb *upcb = nullptr;
ip_addr_t lastAdd;
u16_t lastPort = 0;
bool physicalConnection = false;
MutexIF* bridgeLock = nullptr;
/**
* Check whether the communication link is up.
* Caller must ensure thread-safety by using the bridge lock.
* @return
*/
bool comLinkUp() const;
private:
struct udp_pcb *upcb = nullptr;
ip_addr_t lastAdd;
u16_t lastPort = 0;
bool physicalConnection = false;
MutexIF *bridgeLock = nullptr;
#if TCPIP_RECV_WIRETAPPING == 1
bool connectFlag = false;
bool connectFlag = false;
#endif
/**
* Used to notify bridge about change in the physical ethernet connection.
* Connection does not mean that replies are possible (recipient not set yet), but
* disconnect means that we can't send anything. Caller must ensure thread-safety
* by using the bridge lock.
*/
void physicalConnectStatusChange(bool connect);
/**
* Used to notify bridge about change in the physical ethernet connection.
* Connection does not mean that replies are possible (recipient not set yet), but
* disconnect means that we can't send anything. Caller must ensure thread-safety
* by using the bridge lock.
*/
void physicalConnectStatusChange(bool connect);
};
#endif /* BSP_STM32_RTEMS_NETWORKING_TMTCUDPBRIDGE_H_ */

View File

@ -1,66 +1,60 @@
#include "UdpTcLwIpPollingTask.h"
#include "TmTcLwIpUdpBridge.h"
#include "app_ethernet.h"
#include "ethernetif.h"
#include "app_dhcp.h"
#include "networking.h"
#include <hardware_init.h>
#include "TmTcLwIpUdpBridge.h"
#include "app_dhcp.h"
#include "app_ethernet.h"
#include "ethernetif.h"
#include "fsfw/ipc/MutexGuard.h"
#include "fsfw/serviceinterface/ServiceInterface.h"
#include "fsfw/objectmanager/ObjectManager.h"
#include "fsfw/serviceinterface/ServiceInterface.h"
#include "lwip/timeouts.h"
#include "networking.h"
UdpTcLwIpPollingTask::UdpTcLwIpPollingTask(object_id_t objectId, object_id_t bridgeId,
struct netif* gnetif):
SystemObject(objectId), periodicHandleCounter(0), bridgeId(bridgeId), gnetif(gnetif) {
}
struct netif* gnetif)
: SystemObject(objectId), periodicHandleCounter(0), bridgeId(bridgeId), gnetif(gnetif) {}
UdpTcLwIpPollingTask::~UdpTcLwIpPollingTask() {
}
UdpTcLwIpPollingTask::~UdpTcLwIpPollingTask() {}
ReturnValue_t UdpTcLwIpPollingTask::initialize() {
udpBridge = ObjectManager::instance()->get<TmTcLwIpUdpBridge>(bridgeId);
if(udpBridge == nullptr) {
return ObjectManagerIF::CHILD_INIT_FAILED;
}
if (netif_is_link_up(gnetif)) {
networking::setEthCableConnected(true);
}
return RETURN_OK;
udpBridge = ObjectManager::instance()->get<TmTcLwIpUdpBridge>(bridgeId);
if (udpBridge == nullptr) {
return ObjectManagerIF::CHILD_INIT_FAILED;
}
if (netif_is_link_up(gnetif)) {
networking::setEthCableConnected(true);
}
return RETURN_OK;
}
/* Poll the EMAC Interface and pass content to the network interface (lwIP) */
ReturnValue_t UdpTcLwIpPollingTask::performOperation(uint8_t operationCode) {
/* Read a received packet from the Ethernet buffers and send it
to the lwIP for handling */
ethernetif_input(gnetif);
/* Read a received packet from the Ethernet buffers and send it
to the lwIP for handling */
ethernetif_input(gnetif);
/* Handle timeouts */
sys_check_timeouts();
/* Handle timeouts */
sys_check_timeouts();
#if LWIP_NETIF_LINK_CALLBACK == 1
networking::ethernetLinkPeriodicHandle(gnetif);
networking::ethernetLinkPeriodicHandle(gnetif);
#endif
if(udpBridge != nullptr) {
MutexGuard lg(udpBridge->bridgeLock);
/* In case ethernet cable is disconnected */
if(not networking::getEthCableConnected() and udpBridge->comLinkUp()) {
udpBridge->physicalConnectStatusChange(false);
}
else if(networking::getEthCableConnected() and not udpBridge->comLinkUp()) {
udpBridge->physicalConnectStatusChange(true);
}
if (udpBridge != nullptr) {
MutexGuard lg(udpBridge->bridgeLock);
/* In case ethernet cable is disconnected */
if (not networking::getEthCableConnected() and udpBridge->comLinkUp()) {
udpBridge->physicalConnectStatusChange(false);
} else if (networking::getEthCableConnected() and not udpBridge->comLinkUp()) {
udpBridge->physicalConnectStatusChange(true);
}
}
#if LWIP_DHCP == 1
DHCP_Periodic_Handle(gnetif);
DHCP_Periodic_Handle(gnetif);
#endif
return RETURN_OK;
return RETURN_OK;
}

View File

@ -2,9 +2,8 @@
#define BSP_STM32_RTEMS_EMACPOLLINGTASK_H_
#include <fsfw/objectmanager/SystemObject.h>
#include <fsfw/tasks/ExecutableObjectIF.h>
#include <fsfw/returnvalues/HasReturnvaluesIF.h>
#include <fsfw/tasks/ExecutableObjectIF.h>
#include <lwip/netif.h>
class TmTcLwIpUdpBridge;
@ -13,29 +12,28 @@ class TmTcLwIpUdpBridge;
* @brief Separate task to poll EMAC interface.
* Polled data is passed to the netif (lwIP)
*/
class UdpTcLwIpPollingTask:
public SystemObject,
public ExecutableObjectIF,
public HasReturnvaluesIF {
public:
UdpTcLwIpPollingTask(object_id_t objectId, object_id_t bridgeId, struct netif* gnetif);
virtual ~UdpTcLwIpPollingTask();
class UdpTcLwIpPollingTask : public SystemObject,
public ExecutableObjectIF,
public HasReturnvaluesIF {
public:
UdpTcLwIpPollingTask(object_id_t objectId, object_id_t bridgeId, struct netif* gnetif);
virtual ~UdpTcLwIpPollingTask();
virtual ReturnValue_t initialize() override;
virtual ReturnValue_t initialize() override;
/**
* Executed periodically.
* @param operationCode
* @return
*/
virtual ReturnValue_t performOperation(uint8_t operationCode = 0) override;
private:
static const uint8_t PERIODIC_HANDLE_TRIGGER = 5;
uint8_t periodicHandleCounter;
object_id_t bridgeId = 0;
TmTcLwIpUdpBridge* udpBridge = nullptr;
struct netif* gnetif = nullptr;
/**
* Executed periodically.
* @param operationCode
* @return
*/
virtual ReturnValue_t performOperation(uint8_t operationCode = 0) override;
private:
static const uint8_t PERIODIC_HANDLE_TRIGGER = 5;
uint8_t periodicHandleCounter;
object_id_t bridgeId = 0;
TmTcLwIpUdpBridge* udpBridge = nullptr;
struct netif* gnetif = nullptr;
};
#endif /* BSP_STM32_RTEMS_EMACPOLLINGTASK_H_ */

View File

@ -1,13 +1,12 @@
#include "OBSWConfig.h"
#include "app_dhcp.h"
#include "app_ethernet.h"
#include "networking.h"
#include "udp_config.h"
#include "ethernetif.h"
#include "OBSWConfig.h"
#include "app_ethernet.h"
#include "ethernetif.h"
#include "lwip/dhcp.h"
#include "networking.h"
#include "stm32h7xx_nucleo.h"
#include "udp_config.h"
#if LWIP_DHCP == 1
@ -24,57 +23,56 @@ void handle_dhcp_down(struct netif* netif);
* @param None
* @retval None
*/
void DHCP_Process(struct netif *netif)
{
struct dhcp* dhcp = NULL;
switch (DHCP_state) {
void DHCP_Process(struct netif* netif) {
struct dhcp* dhcp = NULL;
switch (DHCP_state) {
case DHCP_START: {
handle_dhcp_start(netif);
break;
handle_dhcp_start(netif);
break;
}
case DHCP_WAIT_ADDRESS: {
handle_dhcp_wait(netif, &dhcp);
break;
handle_dhcp_wait(netif, &dhcp);
break;
}
case DHCP_LINK_DOWN: {
handle_dhcp_down(netif);
break;
handle_dhcp_down(netif);
break;
}
default: {
break;
}
break;
}
}
}
void handle_dhcp_timeout(struct netif* netif) {
ip_addr_t ipaddr;
ip_addr_t netmask;
ip_addr_t gw;
ip_addr_t ipaddr;
ip_addr_t netmask;
ip_addr_t gw;
DHCP_state = DHCP_TIMEOUT;
DHCP_state = DHCP_TIMEOUT;
/* Stop DHCP */
dhcp_stop(netif);
/* Stop DHCP */
dhcp_stop(netif);
/* Static address used */
networking::setLwipAddresses(&ipaddr, &netmask, &gw);
netif_set_addr(netif, &ipaddr, &netmask, &gw);
/* Static address used */
networking::setLwipAddresses(&ipaddr, &netmask, &gw);
netif_set_addr(netif, &ipaddr, &netmask, &gw);
printf("DHCP Timeout\n\r");
uint8_t iptxt[20];
sprintf((char *)iptxt, "%s", ip4addr_ntoa(netif_ip4_addr(netif)));
printf("Assigning static IP address: %s\n", iptxt);
printf("DHCP Timeout\n\r");
uint8_t iptxt[20];
sprintf((char*)iptxt, "%s", ip4addr_ntoa(netif_ip4_addr(netif)));
printf("Assigning static IP address: %s\n", iptxt);
#if defined FSFW_OSAL_FREERTOS
ETH_HandleTypeDef* handle = getEthernetHandle();
handle->gState = HAL_ETH_STATE_READY;
ETH_HandleTypeDef* handle = getEthernetHandle();
handle->gState = HAL_ETH_STATE_READY;
#endif
#if OBSW_ETHERNET_TMTC_COMMANDING == 1
#if OBSW_ETHERNET_USE_LED1_LED2 == 1
BSP_LED_On(LED1);
BSP_LED_Off(LED2);
BSP_LED_On(LED1);
BSP_LED_Off(LED2);
#endif
#endif
}
@ -84,74 +82,67 @@ void handle_dhcp_timeout(struct netif* netif) {
* @param netif
* @retval None
*/
void DHCP_Periodic_Handle(struct netif *netif)
{
/* Fine DHCP periodic process every 500ms */
if (HAL_GetTick() - DHCPfineTimer >= DHCP_FINE_TIMER_MSECS) {
DHCPfineTimer = HAL_GetTick();
/* process DHCP state machine */
DHCP_Process(netif);
}
void DHCP_Periodic_Handle(struct netif* netif) {
/* Fine DHCP periodic process every 500ms */
if (HAL_GetTick() - DHCPfineTimer >= DHCP_FINE_TIMER_MSECS) {
DHCPfineTimer = HAL_GetTick();
/* process DHCP state machine */
DHCP_Process(netif);
}
}
void handle_dhcp_start(struct netif* netif) {
printf("handle_dhcp_start: Looking for DHCP server ...\n\r");
printf("handle_dhcp_start: Looking for DHCP server ...\n\r");
#if OBSW_ETHERNET_TMTC_COMMANDING == 1
#if OBSW_ETHERNET_USE_LED1_LED2 == 1
BSP_LED_Off(LED1);
BSP_LED_Off(LED2);
BSP_LED_Off(LED1);
BSP_LED_Off(LED2);
#endif
#endif
ip_addr_set_zero_ip4(&netif->ip_addr);
ip_addr_set_zero_ip4(&netif->netmask);
ip_addr_set_zero_ip4(&netif->gw);
dhcp_start(netif);
DHCP_state = DHCP_WAIT_ADDRESS;
ip_addr_set_zero_ip4(&netif->ip_addr);
ip_addr_set_zero_ip4(&netif->netmask);
ip_addr_set_zero_ip4(&netif->gw);
dhcp_start(netif);
DHCP_state = DHCP_WAIT_ADDRESS;
}
void handle_dhcp_wait(struct netif* netif, struct dhcp** dhcp) {
if (dhcp_supplied_address(netif)) {
DHCP_state = DHCP_ADDRESS_ASSIGNED;
printf("IP address assigned by a DHCP server: %s\n\r", ip4addr_ntoa(netif_ip4_addr(netif)));
printf("Listener port: %d\n\r", UDP_SERVER_PORT);
if (dhcp_supplied_address(netif)) {
DHCP_state = DHCP_ADDRESS_ASSIGNED;
printf("IP address assigned by a DHCP server: %s\n\r", ip4addr_ntoa(netif_ip4_addr(netif)));
printf("Listener port: %d\n\r", UDP_SERVER_PORT);
#if OBSW_ETHERNET_TMTC_COMMANDING == 1
#if OBSW_ETHERNET_USE_LED1_LED2 == 1
BSP_LED_On(LED1);
BSP_LED_Off(LED2);
BSP_LED_On(LED1);
BSP_LED_Off(LED2);
#endif
#endif
}
else {
*dhcp = (struct dhcp*) netif_get_client_data(netif, LWIP_NETIF_CLIENT_DATA_INDEX_DHCP);
} else {
*dhcp = (struct dhcp*)netif_get_client_data(netif, LWIP_NETIF_CLIENT_DATA_INDEX_DHCP);
/* DHCP timeout */
if ((*dhcp)->tries > MAX_DHCP_TRIES)
{
handle_dhcp_timeout(netif);
}
/* DHCP timeout */
if ((*dhcp)->tries > MAX_DHCP_TRIES) {
handle_dhcp_timeout(netif);
}
}
}
void handle_dhcp_down(struct netif* netif) {
DHCP_state = DHCP_OFF;
DHCP_state = DHCP_OFF;
#if OBSW_ETHERNET_TMTC_COMMANDING == 1
printf("DHCP_Process: The network cable is not connected.\n\r");
printf("DHCP_Process: The network cable is not connected.\n\r");
#if OBSW_ETHERNET_USE_LED1_LED2 == 1
BSP_LED_Off(LED1);
BSP_LED_On(LED2);
BSP_LED_Off(LED1);
BSP_LED_On(LED2);
#endif
#endif
/* Global boolean to track ethernet connection */
networking::setEthCableConnected(false);
/* Global boolean to track ethernet connection */
networking::setEthCableConnected(false);
}
uint8_t get_dhcp_state() {
return DHCP_state;
}
uint8_t get_dhcp_state() { return DHCP_state; }
void set_dhcp_state(uint8_t new_state) {
DHCP_state = new_state;
}
void set_dhcp_state(uint8_t new_state) { DHCP_state = new_state; }
#endif /* LWIP_DHCP == 1 */

View File

@ -12,12 +12,12 @@ extern "C" {
#include "lwip/netif.h"
/* DHCP process states */
#define DHCP_OFF (uint8_t) 0
#define DHCP_START (uint8_t) 1
#define DHCP_WAIT_ADDRESS (uint8_t) 2
#define DHCP_ADDRESS_ASSIGNED (uint8_t) 3
#define DHCP_TIMEOUT (uint8_t) 4
#define DHCP_LINK_DOWN (uint8_t) 5
#define DHCP_OFF (uint8_t)0
#define DHCP_START (uint8_t)1
#define DHCP_WAIT_ADDRESS (uint8_t)2
#define DHCP_ADDRESS_ASSIGNED (uint8_t)3
#define DHCP_TIMEOUT (uint8_t)4
#define DHCP_LINK_DOWN (uint8_t)5
uint8_t get_dhcp_state();
void set_dhcp_state(uint8_t new_state);

View File

@ -1,17 +1,18 @@
/* Includes ------------------------------------------------------------------*/
#include "app_ethernet.h"
#include "ethernetif.h"
#include "udp_config.h"
#include "networking.h"
#include "udp_config.h"
#if LWIP_DHCP
#include "app_dhcp.h"
#endif
#include <lwipopts.h>
#include <lwip/netif.h>
#include <stm32h7xx_nucleo.h>
#include <OBSWConfig.h>
#include <lwip/netif.h>
#include <lwipopts.h>
#include <stm32h7xx_nucleo.h>
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
@ -22,55 +23,49 @@ uint32_t ethernetLinkTimer = 0;
/* Private function prototypes -----------------------------------------------*/
void handle_status_change(struct netif* netif, bool link_up);
/* Private functions ---------------------------------------------------------*/
/**
* @brief Notify the User about the network interface config status
* @param netif: the network interface
* @retval None
*/
void networking::ethernetLinkStatusUpdated(struct netif *netif)
{
if (netif_is_link_up(netif))
{
networking::setEthCableConnected(true);
handle_status_change(netif, true);
}
else
{
networking::setEthCableConnected(false);
handle_status_change(netif, false);
}
void networking::ethernetLinkStatusUpdated(struct netif* netif) {
if (netif_is_link_up(netif)) {
networking::setEthCableConnected(true);
handle_status_change(netif, true);
} else {
networking::setEthCableConnected(false);
handle_status_change(netif, false);
}
}
void handle_status_change(struct netif* netif, bool link_up) {
if(link_up) {
if (link_up) {
#if LWIP_DHCP
/* Update DHCP state machine */
set_dhcp_state(DHCP_START);
/* Update DHCP state machine */
set_dhcp_state(DHCP_START);
#else
uint8_t iptxt[20];
sprintf((char *)iptxt, "%s", ip4addr_ntoa(netif_ip4_addr(netif)));
printf("\rNetwork cable connected. Static IP address: %s | Port: %d\n\r", iptxt,
UDP_SERVER_PORT);
uint8_t iptxt[20];
sprintf((char*)iptxt, "%s", ip4addr_ntoa(netif_ip4_addr(netif)));
printf("\rNetwork cable connected. Static IP address: %s | Port: %d\n\r", iptxt,
UDP_SERVER_PORT);
#if OBSW_ETHERNET_USE_LED1_LED2 == 1
BSP_LED_On(LED1);
BSP_LED_Off(LED2);
BSP_LED_On(LED1);
BSP_LED_Off(LED2);
#endif
#endif /* LWIP_DHCP */
}
else {
printf("Network cable disconnected\n\r");
} else {
printf("Network cable disconnected\n\r");
#if LWIP_DHCP
/* Update DHCP state machine */
set_dhcp_state(DHCP_LINK_DOWN);
/* Update DHCP state machine */
set_dhcp_state(DHCP_LINK_DOWN);
#else
#if OBSW_ETHERNET_USE_LED1_LED2 == 1
BSP_LED_Off(LED1);
BSP_LED_On(LED2);
BSP_LED_Off(LED1);
BSP_LED_On(LED2);
#endif
#endif /* LWIP_DHCP */
}
}
}
#if LWIP_NETIF_LINK_CALLBACK
@ -80,14 +75,12 @@ void handle_status_change(struct netif* netif, bool link_up) {
* @param netif
* @retval None
*/
void networking::ethernetLinkPeriodicHandle(struct netif *netif)
{
/* Ethernet Link every 100ms */
if (HAL_GetTick() - ethernetLinkTimer >= 100)
{
ethernetLinkTimer = HAL_GetTick();
ethernet_link_check_state(netif);
}
void networking::ethernetLinkPeriodicHandle(struct netif* netif) {
/* Ethernet Link every 100ms */
if (HAL_GetTick() - ethernetLinkTimer >= 100) {
ethernetLinkTimer = HAL_GetTick();
ethernet_link_check_state(netif);
}
}
#endif /* LWIP_NETIF_LINK_CALLBACK */

View File

@ -1,54 +1,54 @@
/**
******************************************************************************
* @file LwIP/LwIP_UDP_Echo_Client/Inc/app_ethernet.h
* @author MCD Application Team
* @brief Header for app_ethernet.c module
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2017 STMicroelectronics International N.V.
* All rights reserved.</center></h2>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted, provided that the following conditions are met:
*
* 1. Redistribution 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 STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* derived from this software without specific written permission.
* 4. This software, including modifications and/or derivative works of this
* software, must execute solely and exclusively on microcontroller or
* microprocessor devices manufactured by or for STMicroelectronics.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
*
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* SHALL STMICROELECTRONICS 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.
*
******************************************************************************
*/
******************************************************************************
* @file LwIP/LwIP_UDP_Echo_Client/Inc/app_ethernet.h
* @author MCD Application Team
* @brief Header for app_ethernet.c module
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2017 STMicroelectronics International N.V.
* All rights reserved.</center></h2>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted, provided that the following conditions are met:
*
* 1. Redistribution 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 STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* derived from this software without specific written permission.
* 4. This software, including modifications and/or derivative works of this
* software, must execute solely and exclusively on microcontroller or
* microprocessor devices manufactured by or for STMicroelectronics.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
*
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* SHALL STMICROELECTRONICS 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.
*
******************************************************************************
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef EXAMPLE_COMMON_APP_ETHERNET_H
#define EXAMPLE_COMMON_APP_ETHERNET_H
#ifdef __cplusplus
extern "C" {
extern "C" {
#endif
/* Includes ------------------------------------------------------------------*/
@ -65,7 +65,7 @@ namespace networking {
void ethernetLinkStatusUpdated(struct netif *netif);
void ethernetLinkPeriodicHandle(struct netif *netif);
}
} // namespace networking
#ifdef __cplusplus
}
@ -73,6 +73,4 @@ void ethernetLinkPeriodicHandle(struct netif *netif);
#endif /* EXAMPLE_COMMON_APP_ETHERNET_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,59 +1,60 @@
/**
******************************************************************************
* @file LwIP/LwIP_UDP_Echo_Client/Src/ethernetif.c
* @author MCD Application Team
* @brief This file implements Ethernet network interface drivers for lwIP
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2017 STMicroelectronics International N.V.
* All rights reserved.</center></h2>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted, provided that the following conditions are met:
*
* 1. Redistribution 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 STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* derived from this software without specific written permission.
* 4. This software, including modifications and/or derivative works of this
* software, must execute solely and exclusively on microcontroller or
* microprocessor devices manufactured by or for STMicroelectronics.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
*
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* SHALL STMICROELECTRONICS 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.
*
******************************************************************************
*/
******************************************************************************
* @file LwIP/LwIP_UDP_Echo_Client/Src/ethernetif.c
* @author MCD Application Team
* @brief This file implements Ethernet network interface drivers for lwIP
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2017 STMicroelectronics International N.V.
* All rights reserved.</center></h2>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted, provided that the following conditions are met:
*
* 1. Redistribution 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 STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* derived from this software without specific written permission.
* 4. This software, including modifications and/or derivative works of this
* software, must execute solely and exclusively on microcontroller or
* microprocessor devices manufactured by or for STMicroelectronics.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
*
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* SHALL STMICROELECTRONICS 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.
*
******************************************************************************
*/
/* Includes ------------------------------------------------------------------*/
#include "fsfw/FSFW.h"
#include "ethernetif.h"
#include <string.h>
#include <lan8742.h>
#include <stm32h7xx_hal.h>
#include <lwip/netif.h>
#include <lwip/opt.h>
#include <lwip/timeouts.h>
#include <netif/etharp.h>
#include <stm32h7xx_hal.h>
#include <string.h>
#include "fsfw/FSFW.h"
#ifdef FSFW_OSAL_RTEMS
#include <rtems.h>
@ -69,17 +70,17 @@
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/*
/*
@Note: This interface is implemented to operate in zero-copy mode only:
- Rx buffers are allocated statically and passed directly to the LwIP stack
they will return back to DMA after been processed by the stack.
- Tx Buffers will be allocated from LwIP stack memory heap,
- Tx Buffers will be allocated from LwIP stack memory heap,
then passed to ETH HAL driver.
@Notes:
1.a. ETH DMA Rx descriptors must be contiguous, the default count is 4,
@Notes:
1.a. ETH DMA Rx descriptors must be contiguous, the default count is 4,
to customize it please redefine ETH_RX_DESC_CNT in stm32xxxx_hal_conf.h
1.b. ETH DMA Tx descriptors must be contiguous, the default count is 4,
1.b. ETH DMA Tx descriptors must be contiguous, the default count is 4,
to customize it please redefine ETH_TX_DESC_CNT in stm32xxxx_hal_conf.h
2.a. Rx Buffers number must be between ETH_RX_DESC_CNT and 2*ETH_RX_DESC_CNT
@ -87,35 +88,45 @@
passed to ETH DMA in the init field (EthHandle.Init.RxBuffLen)
*/
#if defined ( __ICCARM__ ) /*!< IAR Compiler */
#if defined(__ICCARM__) /*!< IAR Compiler */
#pragma location=0x30040000
ETH_DMADescTypeDef DMARxDscrTab[ETH_RX_DESC_CNT]; /* Ethernet Rx DMA Descriptors */
#pragma location=0x30040060
ETH_DMADescTypeDef DMATxDscrTab[ETH_TX_DESC_CNT]; /* Ethernet Tx DMA Descriptors */
#pragma location=0x30040200
#pragma location = 0x30040000
ETH_DMADescTypeDef DMARxDscrTab[ETH_RX_DESC_CNT]; /* Ethernet Rx DMA Descriptors */
#pragma location = 0x30040060
ETH_DMADescTypeDef DMATxDscrTab[ETH_TX_DESC_CNT]; /* Ethernet Tx DMA Descriptors */
#pragma location = 0x30040200
uint8_t Rx_Buff[ETH_RX_DESC_CNT][ETH_RX_BUFFER_SIZE]; /* Ethernet Receive Buffers */
#elif defined ( __CC_ARM ) /* MDK ARM Compiler */
#elif defined(__CC_ARM) /* MDK ARM Compiler */
__attribute__((section(".RxDecripSection"))) ETH_DMADescTypeDef DMARxDscrTab[ETH_RX_DESC_CNT]; /* Ethernet Rx DMA Descriptors */
__attribute__((section(".TxDecripSection"))) ETH_DMADescTypeDef DMATxDscrTab[ETH_TX_DESC_CNT]; /* Ethernet Tx DMA Descriptors */
__attribute__((section(".RxArraySection"))) uint8_t Rx_Buff[ETH_RX_DESC_CNT][ETH_RX_BUFFER_SIZE]; /* Ethernet Receive Buffer */
__attribute__((section(".RxDecripSection")))
ETH_DMADescTypeDef DMARxDscrTab[ETH_RX_DESC_CNT]; /* Ethernet Rx DMA Descriptors */
__attribute__((section(".TxDecripSection")))
ETH_DMADescTypeDef DMATxDscrTab[ETH_TX_DESC_CNT]; /* Ethernet Tx DMA Descriptors */
__attribute__((section(".RxArraySection")))
uint8_t Rx_Buff[ETH_RX_DESC_CNT][ETH_RX_BUFFER_SIZE]; /* Ethernet Receive Buffer */
#elif defined ( __GNUC__ ) /* GNU Compiler */
#elif defined(__GNUC__) /* GNU Compiler */
#ifdef FSFW_OSAL_RTEMS
/* Put into special RTEMS section and align correctly */
ETH_DMADescTypeDef DMARxDscrTab[ETH_RX_DESC_CNT] __attribute__((section(".bsp_nocache"), __aligned__(DMA_DESCRIPTOR_ALIGNMENT))); /* Ethernet Rx DMA Descriptors */
ETH_DMADescTypeDef DMARxDscrTab[ETH_RX_DESC_CNT]
__attribute__((section(".bsp_nocache"),
__aligned__(DMA_DESCRIPTOR_ALIGNMENT))); /* Ethernet Rx DMA Descriptors */
/* Put into special RTEMS section and align correctly */
ETH_DMADescTypeDef DMATxDscrTab[ETH_TX_DESC_CNT] __attribute__((section(".bsp_nocache"), __aligned__(DMA_DESCRIPTOR_ALIGNMENT))); /* Ethernet Tx DMA Descriptors */
ETH_DMADescTypeDef DMATxDscrTab[ETH_TX_DESC_CNT]
__attribute__((section(".bsp_nocache"),
__aligned__(DMA_DESCRIPTOR_ALIGNMENT))); /* Ethernet Tx DMA Descriptors */
/* Ethernet Receive Buffers. Just place somewhere is BSS instead of explicitely placing it */
uint8_t Rx_Buff[ETH_RX_DESC_CNT][ETH_RX_BUFFER_SIZE];
#elif defined FSFW_OSAL_FREERTOS
/* Placement and alignment specified in linker script here */
ETH_DMADescTypeDef DMARxDscrTab[ETH_RX_DESC_CNT] __attribute__((section(".RxDecripSection"))); /* Ethernet Rx DMA Descriptors */
ETH_DMADescTypeDef DMATxDscrTab[ETH_TX_DESC_CNT] __attribute__((section(".TxDecripSection"))); /* Ethernet Tx DMA Descriptors */
uint8_t Rx_Buff[ETH_RX_DESC_CNT][ETH_RX_BUFFER_SIZE] __attribute__((section(".RxArraySection"))); /* Ethernet Receive Buffers */
ETH_DMADescTypeDef DMARxDscrTab[ETH_RX_DESC_CNT]
__attribute__((section(".RxDecripSection"))); /* Ethernet Rx DMA Descriptors */
ETH_DMADescTypeDef DMATxDscrTab[ETH_TX_DESC_CNT]
__attribute__((section(".TxDecripSection"))); /* Ethernet Tx DMA Descriptors */
uint8_t Rx_Buff[ETH_RX_DESC_CNT][ETH_RX_BUFFER_SIZE]
__attribute__((section(".RxArraySection"))); /* Ethernet Receive Buffers */
#endif /* FSFW_FREERTOS */
#endif /* defined ( __GNUC__ ) */
@ -124,10 +135,10 @@ uint8_t Rx_Buff[ETH_RX_DESC_CNT][ETH_RX_BUFFER_SIZE] __attribute__((section(".Rx
bool ethernet_cable_connected;
struct pbuf_custom rx_pbuf[ETH_RX_DESC_CNT];
uint32_t current_pbuf_idx =0;
uint32_t current_pbuf_idx = 0;
ETH_HandleTypeDef EthHandle;
ETH_TxPacketConfig TxConfig;
ETH_TxPacketConfig TxConfig;
lan8742_Object_t LAN8742;
@ -136,71 +147,66 @@ u32_t sys_now(void);
void pbuf_free_custom(struct pbuf *p);
int32_t ETH_PHY_IO_Init(void);
int32_t ETH_PHY_IO_DeInit (void);
int32_t ETH_PHY_IO_DeInit(void);
int32_t ETH_PHY_IO_ReadReg(uint32_t DevAddr, uint32_t RegAddr, uint32_t *pRegVal);
int32_t ETH_PHY_IO_WriteReg(uint32_t DevAddr, uint32_t RegAddr, uint32_t RegVal);
int32_t ETH_PHY_IO_GetTick(void);
lan8742_IOCtx_t LAN8742_IOCtx = {ETH_PHY_IO_Init,
ETH_PHY_IO_DeInit,
ETH_PHY_IO_WriteReg,
ETH_PHY_IO_ReadReg,
ETH_PHY_IO_GetTick};
lan8742_IOCtx_t LAN8742_IOCtx = {ETH_PHY_IO_Init, ETH_PHY_IO_DeInit, ETH_PHY_IO_WriteReg,
ETH_PHY_IO_ReadReg, ETH_PHY_IO_GetTick};
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
LL Driver Interface ( LwIP stack --> ETH)
LL Driver Interface ( LwIP stack --> ETH)
*******************************************************************************/
/**
* @brief In this function, the hardware should be initialized.
* Called from ethernetif_init().
*
* @param netif the already initialized lwip network interface structure
* for this ethernetif
*/
static void low_level_init(struct netif *netif)
{
* @brief In this function, the hardware should be initialized.
* Called from ethernetif_init().
*
* @param netif the already initialized lwip network interface structure
* for this ethernetif
*/
static void low_level_init(struct netif *netif) {
uint32_t idx = 0;
uint8_t macaddress[6]= {ETH_MAC_ADDR0, ETH_MAC_ADDR1, ETH_MAC_ADDR2, ETH_MAC_ADDR3, ETH_MAC_ADDR4, ETH_MAC_ADDR5};
EthHandle.Instance = ETH;
uint8_t macaddress[6] = {ETH_MAC_ADDR0, ETH_MAC_ADDR1, ETH_MAC_ADDR2,
ETH_MAC_ADDR3, ETH_MAC_ADDR4, ETH_MAC_ADDR5};
EthHandle.Instance = ETH;
EthHandle.Init.MACAddr = macaddress;
EthHandle.Init.MediaInterface = HAL_ETH_RMII_MODE;
EthHandle.Init.RxDesc = DMARxDscrTab;
EthHandle.Init.TxDesc = DMATxDscrTab;
EthHandle.Init.RxBuffLen = ETH_RX_BUFFER_SIZE;
/* configure ethernet peripheral (GPIOs, clocks, MAC, DMA) */
HAL_ETH_Init(&EthHandle);
/* set MAC hardware address length */
netif->hwaddr_len = ETHARP_HWADDR_LEN;
/* set MAC hardware address */
netif->hwaddr[0] = 0x02;
netif->hwaddr[1] = 0x00;
netif->hwaddr[2] = 0x00;
netif->hwaddr[3] = 0x00;
netif->hwaddr[4] = 0x00;
netif->hwaddr[5] = 0x00;
netif->hwaddr[0] = 0x02;
netif->hwaddr[1] = 0x00;
netif->hwaddr[2] = 0x00;
netif->hwaddr[3] = 0x00;
netif->hwaddr[4] = 0x00;
netif->hwaddr[5] = 0x00;
/* maximum transfer unit */
netif->mtu = ETH_MAX_PAYLOAD;
/* device capabilities */
/* don't set NETIF_FLAG_ETHARP if this device is not an ethernet one */
netif->flags |= NETIF_FLAG_BROADCAST | NETIF_FLAG_ETHARP;
for(idx = 0; idx < ETH_RX_DESC_CNT; idx ++)
{
for (idx = 0; idx < ETH_RX_DESC_CNT; idx++) {
HAL_ETH_DescAssignMemory(&EthHandle, idx, Rx_Buff[idx], NULL);
/* Set Custom pbuf free function */
rx_pbuf[idx].custom_free_function = pbuf_free_custom;
}
/* Set Tx packet config common parameters */
memset(&TxConfig, 0 , sizeof(ETH_TxPacketConfig));
memset(&TxConfig, 0, sizeof(ETH_TxPacketConfig));
TxConfig.Attributes = ETH_TX_PACKETS_FEATURES_CSUM | ETH_TX_PACKETS_FEATURES_CRCPAD;
TxConfig.ChecksumCtrl = ETH_CHECKSUM_IPHDR_PAYLOAD_INSERT_PHDR_CALC;
TxConfig.CRCPadCtrl = ETH_CRC_PAD_INSERT;
@ -212,47 +218,41 @@ static void low_level_init(struct netif *netif)
LAN8742_Init(&LAN8742);
ethernet_link_check_state(netif);
}
/**
* @brief This function should do the actual transmission of the packet. The packet is
* contained in the pbuf that is passed to the function. This pbuf
* might be chained.
*
* @param netif the lwip network interface structure for this ethernetif
* @param p the MAC packet to send (e.g. IP packet including MAC addresses and type)
* @return ERR_OK if the packet could be sent
* an err_t value if the packet couldn't be sent
*
* @note Returning ERR_MEM here if a DMA queue of your MAC is full can lead to
* strange results. You might consider waiting for space in the DMA queue
* to become availale since the stack doesn't retry to send a packet
* dropped because of memory failure (except for the TCP timers).
*/
static err_t low_level_output(struct netif *netif, struct pbuf *p)
{
uint32_t i=0, framelen = 0;
* @brief This function should do the actual transmission of the packet. The packet is
* contained in the pbuf that is passed to the function. This pbuf
* might be chained.
*
* @param netif the lwip network interface structure for this ethernetif
* @param p the MAC packet to send (e.g. IP packet including MAC addresses and type)
* @return ERR_OK if the packet could be sent
* an err_t value if the packet couldn't be sent
*
* @note Returning ERR_MEM here if a DMA queue of your MAC is full can lead to
* strange results. You might consider waiting for space in the DMA queue
* to become availale since the stack doesn't retry to send a packet
* dropped because of memory failure (except for the TCP timers).
*/
static err_t low_level_output(struct netif *netif, struct pbuf *p) {
uint32_t i = 0, framelen = 0;
struct pbuf *q;
err_t errval = ERR_OK;
ETH_BufferTypeDef Txbuffer[ETH_TX_DESC_CNT];
for(q = p; q != NULL; q = q->next)
{
if(i >= ETH_TX_DESC_CNT)
return ERR_IF;
for (q = p; q != NULL; q = q->next) {
if (i >= ETH_TX_DESC_CNT) return ERR_IF;
Txbuffer[i].buffer = q->payload;
Txbuffer[i].len = q->len;
framelen += q->len;
if(i>0)
{
Txbuffer[i-1].next = &Txbuffer[i];
if (i > 0) {
Txbuffer[i - 1].next = &Txbuffer[i];
}
if(q->next == NULL)
{
if (q->next == NULL) {
Txbuffer[i].next = NULL;
}
@ -264,67 +264,60 @@ static err_t low_level_output(struct netif *netif, struct pbuf *p)
HAL_StatusTypeDef ret = HAL_ETH_Transmit(&EthHandle, &TxConfig, 20);
if(ret != HAL_OK) {
printf("low_level_output: Could not transmit ethernet packet, code %d!\n\r", ret);
if (ret != HAL_OK) {
printf("low_level_output: Could not transmit ethernet packet, code %d!\n\r", ret);
}
return errval;
}
/**
* @brief Should allocate a pbuf and transfer the bytes of the incoming
* packet from the interface into the pbuf.
*
* @param netif the lwip network interface structure for this ethernetif
* @return a pbuf filled with the received packet (including MAC header)
* NULL on memory error
*/
static struct pbuf * low_level_input(struct netif *netif)
{
* @brief Should allocate a pbuf and transfer the bytes of the incoming
* packet from the interface into the pbuf.
*
* @param netif the lwip network interface structure for this ethernetif
* @return a pbuf filled with the received packet (including MAC header)
* NULL on memory error
*/
static struct pbuf *low_level_input(struct netif *netif) {
struct pbuf *p = NULL;
ETH_BufferTypeDef RxBuff;
uint32_t framelength = 0;
if (HAL_ETH_IsRxDataAvailable(&EthHandle))
{
if (HAL_ETH_IsRxDataAvailable(&EthHandle)) {
HAL_ETH_GetRxDataBuffer(&EthHandle, &RxBuff);
HAL_ETH_GetRxDataLength(&EthHandle, &framelength);
/* Invalidate data cache for ETH Rx Buffers */
SCB_InvalidateDCache_by_Addr((uint32_t *)Rx_Buff, (ETH_RX_DESC_CNT*ETH_RX_BUFFER_SIZE));
p = pbuf_alloced_custom(PBUF_RAW, framelength, PBUF_POOL, &rx_pbuf[current_pbuf_idx], RxBuff.buffer, ETH_RX_BUFFER_SIZE);
if(current_pbuf_idx < (ETH_RX_DESC_CNT -1))
{
SCB_InvalidateDCache_by_Addr((uint32_t *)Rx_Buff, (ETH_RX_DESC_CNT * ETH_RX_BUFFER_SIZE));
p = pbuf_alloced_custom(PBUF_RAW, framelength, PBUF_POOL, &rx_pbuf[current_pbuf_idx],
RxBuff.buffer, ETH_RX_BUFFER_SIZE);
if (current_pbuf_idx < (ETH_RX_DESC_CNT - 1)) {
current_pbuf_idx++;
}
else
{
} else {
current_pbuf_idx = 0;
}
return p;
}
else
{
} else {
return NULL;
}
}
/**
* @brief This function is the ethernetif_input task, it is processed when a packet
* is ready to be read from the interface. It uses the function low_level_input()
* that should handle the actual reception of bytes from the network
* interface. Then the type of the received packet is determined and
* the appropriate input function is called.
*
* @param netif the lwip network interface structure for this ethernetif
*/
void ethernetif_input(struct netif *netif)
{
* @brief This function is the ethernetif_input task, it is processed when a packet
* is ready to be read from the interface. It uses the function low_level_input()
* that should handle the actual reception of bytes from the network
* interface. Then the type of the received packet is determined and
* the appropriate input function is called.
*
* @param netif the lwip network interface structure for this ethernetif
*/
void ethernetif_input(struct netif *netif) {
err_t err;
struct pbuf *p;
/* move received packet into a new pbuf */
p = low_level_input(netif);
@ -334,8 +327,7 @@ void ethernetif_input(struct netif *netif)
/* entry point to the LwIP stack */
err = netif->input(p, netif);
if (err != ERR_OK)
{
if (err != ERR_OK) {
LWIP_DEBUGF(NETIF_DEBUG, ("ethernetif_input: IP input error\n"));
pbuf_free(p);
p = NULL;
@ -345,19 +337,18 @@ void ethernetif_input(struct netif *netif)
}
/**
* @brief Should be called at the beginning of the program to set up the
* network interface. It calls the function low_level_init() to do the
* actual setup of the hardware.
*
* This function should be passed as a parameter to netif_add().
*
* @param netif the lwip network interface structure for this ethernetif
* @return ERR_OK if the loopif is initialized
* ERR_MEM if private data couldn't be allocated
* any other err_t on error
*/
err_t ethernetif_init(struct netif *netif)
{
* @brief Should be called at the beginning of the program to set up the
* network interface. It calls the function low_level_init() to do the
* actual setup of the hardware.
*
* This function should be passed as a parameter to netif_add().
*
* @param netif the lwip network interface structure for this ethernetif
* @return ERR_OK if the loopif is initialized
* ERR_MEM if private data couldn't be allocated
* any other err_t on error
*/
err_t ethernetif_init(struct netif *netif) {
LWIP_ASSERT("netif != NULL", (netif != NULL));
#if LWIP_NETIF_HOSTNAME
@ -381,14 +372,12 @@ err_t ethernetif_init(struct netif *netif)
}
/**
* @brief Custom Rx pbuf free callback
* @param pbuf: pbuf to be freed
* @retval None
*/
void pbuf_free_custom(struct pbuf *p)
{
if(p != NULL)
{
* @brief Custom Rx pbuf free callback
* @param pbuf: pbuf to be freed
* @retval None
*/
void pbuf_free_custom(struct pbuf *p) {
if (p != NULL) {
p->flags = 0;
p->next = NULL;
p->len = p->tot_len = 0;
@ -398,37 +387,33 @@ void pbuf_free_custom(struct pbuf *p)
}
/**
* @brief Returns the current time in milliseconds
* when LWIP_TIMERS == 1 and NO_SYS == 1
* @param None
* @retval Current Time value
*/
u32_t sys_now(void)
{
return HAL_GetTick();
}
* @brief Returns the current time in milliseconds
* when LWIP_TIMERS == 1 and NO_SYS == 1
* @param None
* @retval Current Time value
*/
u32_t sys_now(void) { return HAL_GetTick(); }
/*******************************************************************************
Ethernet MSP Routines
*******************************************************************************/
/**
* @brief Initializes the ETH MSP.
* @param heth: ETH handle
* @retval None
*/
void HAL_ETH_MspInit(ETH_HandleTypeDef *heth)
{
* @brief Initializes the ETH MSP.
* @param heth: ETH handle
* @retval None
*/
void HAL_ETH_MspInit(ETH_HandleTypeDef *heth) {
GPIO_InitTypeDef GPIO_InitStructure;
/* Ethernett MSP init: RMII Mode */
/* Enable GPIOs clocks */
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOB_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
__HAL_RCC_GPIOG_CLK_ENABLE();
/* Ethernet pins configuration ************************************************/
/* Ethernet pins configuration ************************************************/
/*
RMII_REF_CLK ----------------------> PA1
RMII_MDIO -------------------------> PA2
@ -445,29 +430,29 @@ void HAL_ETH_MspInit(ETH_HandleTypeDef *heth)
/* Configure PA1, PA2 and PA7 */
GPIO_InitStructure.Speed = GPIO_SPEED_FREQ_HIGH;
GPIO_InitStructure.Mode = GPIO_MODE_AF_PP;
GPIO_InitStructure.Pull = GPIO_NOPULL;
GPIO_InitStructure.Pull = GPIO_NOPULL;
GPIO_InitStructure.Alternate = GPIO_AF11_ETH;
GPIO_InitStructure.Pin = GPIO_PIN_1 | GPIO_PIN_2 | GPIO_PIN_7;
HAL_GPIO_Init(GPIOA, &GPIO_InitStructure);
/* Configure PB13 */
GPIO_InitStructure.Pin = GPIO_PIN_13;
HAL_GPIO_Init(GPIOB, &GPIO_InitStructure);
/* Configure PC1, PC4 and PC5 */
GPIO_InitStructure.Pin = GPIO_PIN_1 | GPIO_PIN_4 | GPIO_PIN_5;
HAL_GPIO_Init(GPIOC, &GPIO_InitStructure);
/* Configure PG2, PG11, PG13 and PG14 */
GPIO_InitStructure.Pin = GPIO_PIN_2 | GPIO_PIN_11 | GPIO_PIN_13;
HAL_GPIO_Init(GPIOG, &GPIO_InitStructure);
GPIO_InitStructure.Pin = GPIO_PIN_2 | GPIO_PIN_11 | GPIO_PIN_13;
HAL_GPIO_Init(GPIOG, &GPIO_InitStructure);
#if NO_SYS == 0
/* Enable the Ethernet global Interrupt */
HAL_NVIC_SetPriority(ETH_IRQn, 0x7, 0);
HAL_NVIC_EnableIRQ(ETH_IRQn);
#endif
/* Enable Ethernet clocks */
__HAL_RCC_ETH1MAC_CLK_ENABLE();
__HAL_RCC_ETH1TX_CLK_ENABLE();
@ -478,123 +463,106 @@ void HAL_ETH_MspInit(ETH_HandleTypeDef *heth)
PHI IO Functions
*******************************************************************************/
/**
* @brief Initializes the MDIO interface GPIO and clocks.
* @param None
* @retval 0 if OK, -1 if ERROR
*/
int32_t ETH_PHY_IO_Init(void)
{
* @brief Initializes the MDIO interface GPIO and clocks.
* @param None
* @retval 0 if OK, -1 if ERROR
*/
int32_t ETH_PHY_IO_Init(void) {
/* We assume that MDIO GPIO configuration is already done
in the ETH_MspInit() else it should be done here
in the ETH_MspInit() else it should be done here
*/
/* Configure the MDIO Clock */
HAL_ETH_SetMDIOClockRange(&EthHandle);
return 0;
}
/**
* @brief De-Initializes the MDIO interface .
* @param None
* @retval 0 if OK, -1 if ERROR
*/
int32_t ETH_PHY_IO_DeInit (void)
{
return 0;
}
* @brief De-Initializes the MDIO interface .
* @param None
* @retval 0 if OK, -1 if ERROR
*/
int32_t ETH_PHY_IO_DeInit(void) { return 0; }
/**
* @brief Read a PHY register through the MDIO interface.
* @param DevAddr: PHY port address
* @param RegAddr: PHY register address
* @param pRegVal: pointer to hold the register value
* @retval 0 if OK -1 if Error
*/
int32_t ETH_PHY_IO_ReadReg(uint32_t DevAddr, uint32_t RegAddr, uint32_t *pRegVal)
{
if(HAL_ETH_ReadPHYRegister(&EthHandle, DevAddr, RegAddr, pRegVal) != HAL_OK)
{
* @brief Read a PHY register through the MDIO interface.
* @param DevAddr: PHY port address
* @param RegAddr: PHY register address
* @param pRegVal: pointer to hold the register value
* @retval 0 if OK -1 if Error
*/
int32_t ETH_PHY_IO_ReadReg(uint32_t DevAddr, uint32_t RegAddr, uint32_t *pRegVal) {
if (HAL_ETH_ReadPHYRegister(&EthHandle, DevAddr, RegAddr, pRegVal) != HAL_OK) {
return -1;
}
return 0;
}
/**
* @brief Write a value to a PHY register through the MDIO interface.
* @param DevAddr: PHY port address
* @param RegAddr: PHY register address
* @param RegVal: Value to be written
* @retval 0 if OK -1 if Error
*/
int32_t ETH_PHY_IO_WriteReg(uint32_t DevAddr, uint32_t RegAddr, uint32_t RegVal)
{
if(HAL_ETH_WritePHYRegister(&EthHandle, DevAddr, RegAddr, RegVal) != HAL_OK)
{
* @brief Write a value to a PHY register through the MDIO interface.
* @param DevAddr: PHY port address
* @param RegAddr: PHY register address
* @param RegVal: Value to be written
* @retval 0 if OK -1 if Error
*/
int32_t ETH_PHY_IO_WriteReg(uint32_t DevAddr, uint32_t RegAddr, uint32_t RegVal) {
if (HAL_ETH_WritePHYRegister(&EthHandle, DevAddr, RegAddr, RegVal) != HAL_OK) {
return -1;
}
return 0;
}
/**
* @brief Get the time in millisecons used for internal PHY driver process.
* @retval Time value
*/
int32_t ETH_PHY_IO_GetTick(void)
{
return HAL_GetTick();
}
* @brief Get the time in millisecons used for internal PHY driver process.
* @retval Time value
*/
int32_t ETH_PHY_IO_GetTick(void) { return HAL_GetTick(); }
/**
* @brief
* @retval None
*/
void ethernet_link_check_state(struct netif *netif)
{
* @brief
* @retval None
*/
void ethernet_link_check_state(struct netif *netif) {
ETH_MACConfigTypeDef MACConf;
uint32_t PHYLinkState;
uint32_t linkchanged = 0, speed = 0, duplex =0;
uint32_t linkchanged = 0, speed = 0, duplex = 0;
PHYLinkState = LAN8742_GetLinkState(&LAN8742);
if(netif_is_link_up(netif) && (PHYLinkState <= LAN8742_STATUS_LINK_DOWN))
{
if (netif_is_link_up(netif) && (PHYLinkState <= LAN8742_STATUS_LINK_DOWN)) {
HAL_ETH_Stop(&EthHandle);
netif_set_down(netif);
netif_set_link_down(netif);
}
else if(!netif_is_link_up(netif) && (PHYLinkState > LAN8742_STATUS_LINK_DOWN))
{
switch (PHYLinkState)
{
case LAN8742_STATUS_100MBITS_FULLDUPLEX:
duplex = ETH_FULLDUPLEX_MODE;
speed = ETH_SPEED_100M;
linkchanged = 1;
break;
case LAN8742_STATUS_100MBITS_HALFDUPLEX:
duplex = ETH_HALFDUPLEX_MODE;
speed = ETH_SPEED_100M;
linkchanged = 1;
break;
case LAN8742_STATUS_10MBITS_FULLDUPLEX:
duplex = ETH_FULLDUPLEX_MODE;
speed = ETH_SPEED_10M;
linkchanged = 1;
break;
case LAN8742_STATUS_10MBITS_HALFDUPLEX:
duplex = ETH_HALFDUPLEX_MODE;
speed = ETH_SPEED_10M;
linkchanged = 1;
break;
default:
break;
} else if (!netif_is_link_up(netif) && (PHYLinkState > LAN8742_STATUS_LINK_DOWN)) {
switch (PHYLinkState) {
case LAN8742_STATUS_100MBITS_FULLDUPLEX:
duplex = ETH_FULLDUPLEX_MODE;
speed = ETH_SPEED_100M;
linkchanged = 1;
break;
case LAN8742_STATUS_100MBITS_HALFDUPLEX:
duplex = ETH_HALFDUPLEX_MODE;
speed = ETH_SPEED_100M;
linkchanged = 1;
break;
case LAN8742_STATUS_10MBITS_FULLDUPLEX:
duplex = ETH_FULLDUPLEX_MODE;
speed = ETH_SPEED_10M;
linkchanged = 1;
break;
case LAN8742_STATUS_10MBITS_HALFDUPLEX:
duplex = ETH_HALFDUPLEX_MODE;
speed = ETH_SPEED_10M;
linkchanged = 1;
break;
default:
break;
}
if(linkchanged)
{
if (linkchanged) {
/* Get MAC Config MAC */
HAL_ETH_GetMACConfig(&EthHandle, &MACConf);
MACConf.DuplexMode = duplex;
@ -607,8 +575,6 @@ void ethernet_link_check_state(struct netif *netif)
}
}
ETH_HandleTypeDef* getEthernetHandle() {
return &EthHandle;
}
ETH_HandleTypeDef *getEthernetHandle() { return &EthHandle; }
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,65 +1,66 @@
/**
******************************************************************************
* @file LwIP/LwIP_HTTP_Server_Netconn_RTOS/Inc/ethernetif.h
* @author MCD Application Team
* @brief Header for ethernetif.c module
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2017 STMicroelectronics International N.V.
* All rights reserved.</center></h2>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted, provided that the following conditions are met:
*
* 1. Redistribution 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 STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* derived from this software without specific written permission.
* 4. This software, including modifications and/or derivative works of this
* software, must execute solely and exclusively on microcontroller or
* microprocessor devices manufactured by or for STMicroelectronics.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
*
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* SHALL STMICROELECTRONICS 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.
*
******************************************************************************
*/
******************************************************************************
* @file LwIP/LwIP_HTTP_Server_Netconn_RTOS/Inc/ethernetif.h
* @author MCD Application Team
* @brief Header for ethernetif.c module
******************************************************************************
* @attention
*
* <h2><center>&copy; Copyright (c) 2017 STMicroelectronics International N.V.
* All rights reserved.</center></h2>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted, provided that the following conditions are met:
*
* 1. Redistribution 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 STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* derived from this software without specific written permission.
* 4. This software, including modifications and/or derivative works of this
* software, must execute solely and exclusively on microcontroller or
* microprocessor devices manufactured by or for STMicroelectronics.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
*
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* SHALL STMICROELECTRONICS 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.
*
******************************************************************************
*/
#ifndef __ETHERNETIF_H__
#define __ETHERNETIF_H__
#include <stdbool.h>
#include <stm32h7xx_hal.h>
#include "lwip/err.h"
#include "lwip/netif.h"
#include <stm32h7xx_hal.h>
#include <stdbool.h>
#ifdef __cplusplus
extern "C" {
#endif
#define ETH_RX_BUFFER_SIZE (1536UL)
#define ETH_RX_BUFFER_SIZE (1536UL)
/* Exported types ------------------------------------------------------------*/
ETH_HandleTypeDef* getEthernetHandle();
ETH_HandleTypeDef *getEthernetHandle();
err_t ethernetif_init(struct netif *netif);
void ethernetif_input(struct netif *netif);
void ethernet_link_check_state(struct netif *netif);

View File

@ -1,19 +1,15 @@
#include "udp_config.h"
#include "networking.h"
#include "udp_config.h"
bool ethernetCableConnected = false;
void networking::setEthCableConnected(bool status) {
ethernetCableConnected = status;
}
void networking::setEthCableConnected(bool status) { ethernetCableConnected = status; }
bool networking::getEthCableConnected() {
return ethernetCableConnected;
}
bool networking::getEthCableConnected() { return ethernetCableConnected; }
void networking::setLwipAddresses(ip_addr_t* ipaddr, ip_addr_t* netmask, ip_addr_t* gw) {
IP4_ADDR(ipaddr, IP_ADDR0, IP_ADDR1, IP_ADDR2, IP_ADDR3);
IP4_ADDR(netmask, NETMASK_ADDR0, NETMASK_ADDR1 ,
NETMASK_ADDR2, NETMASK_ADDR3);
IP4_ADDR(gw, GW_ADDR0, GW_ADDR1, GW_ADDR2, GW_ADDR3);
IP4_ADDR(ipaddr, IP_ADDR0, IP_ADDR1, IP_ADDR2, IP_ADDR3);
IP4_ADDR(netmask, NETMASK_ADDR0, NETMASK_ADDR1, NETMASK_ADDR2, NETMASK_ADDR3);
IP4_ADDR(gw, GW_ADDR0, GW_ADDR1, GW_ADDR2, GW_ADDR3);
}

View File

@ -9,6 +9,6 @@ void setEthCableConnected(bool status);
bool getEthCableConnected();
void setLwipAddresses(ip_addr_t* ipaddr, ip_addr_t* netmask, ip_addr_t* gw);
}
} // namespace networking
#endif /* BSP_STM32H7_RTEMS_NETWORKING_NETWORKING_H_ */

View File

@ -6,31 +6,31 @@ extern "C" {
#endif
/* UDP local connection port. Client needs to bind to this port */
#define UDP_SERVER_PORT 7
#define UDP_SERVER_PORT 7
/*Static DEST IP ADDRESS: DEST_IP_ADDR0.DEST_IP_ADDR1.DEST_IP_ADDR2.DEST_IP_ADDR3 */
#define DEST_IP_ADDR0 ((uint8_t)169U)
#define DEST_IP_ADDR1 ((uint8_t)254U)
#define DEST_IP_ADDR2 ((uint8_t)39U)
#define DEST_IP_ADDR3 ((uint8_t)2U)
#define DEST_IP_ADDR0 ((uint8_t)169U)
#define DEST_IP_ADDR1 ((uint8_t)254U)
#define DEST_IP_ADDR2 ((uint8_t)39U)
#define DEST_IP_ADDR3 ((uint8_t)2U)
/*Static IP ADDRESS*/
#define IP_ADDR0 169
#define IP_ADDR1 254
#define IP_ADDR2 1
#define IP_ADDR3 38
#define IP_ADDR0 169
#define IP_ADDR1 254
#define IP_ADDR2 1
#define IP_ADDR3 38
/*NETMASK*/
#define NETMASK_ADDR0 255
#define NETMASK_ADDR1 255
#define NETMASK_ADDR2 0
#define NETMASK_ADDR3 0
#define NETMASK_ADDR0 255
#define NETMASK_ADDR1 255
#define NETMASK_ADDR2 0
#define NETMASK_ADDR3 0
/*Gateway Address*/
#define GW_ADDR0 192
#define GW_ADDR1 168
#define GW_ADDR2 178
#define GW_ADDR3 1
#define GW_ADDR0 192
#define GW_ADDR1 168
#define GW_ADDR2 178
#define GW_ADDR3 1
#ifdef __cplusplus
}