Welcome to mirror list, hosted at ThFree Co, Russian Federation.

github.com/Duet3D/RepRapFirmware.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
Diffstat (limited to 'src/Networking/LwipEthernet')
-rw-r--r--src/Networking/LwipEthernet/GMAC/ethernet_sam.cpp4
-rw-r--r--src/Networking/LwipEthernet/GMAC/ethernet_sam.h3
-rw-r--r--src/Networking/LwipEthernet/GMAC/same70_gmac.cpp263
-rw-r--r--src/Networking/LwipEthernet/GMAC/same70_gmac.h9
-rw-r--r--src/Networking/LwipEthernet/Lwip/lwipopts.h11
-rw-r--r--src/Networking/LwipEthernet/LwipEthernetInterface.cpp190
-rw-r--r--src/Networking/LwipEthernet/LwipEthernetInterface.h2
-rw-r--r--src/Networking/LwipEthernet/LwipSocket.cpp101
-rw-r--r--src/Networking/LwipEthernet/LwipSocket.h2
9 files changed, 343 insertions, 242 deletions
diff --git a/src/Networking/LwipEthernet/GMAC/ethernet_sam.cpp b/src/Networking/LwipEthernet/GMAC/ethernet_sam.cpp
index a1ac7db8..e706a153 100644
--- a/src/Networking/LwipEthernet/GMAC/ethernet_sam.cpp
+++ b/src/Networking/LwipEthernet/GMAC/ethernet_sam.cpp
@@ -59,8 +59,6 @@ extern "C" {
#include "lwip/stats.h"
#include "lwip/sys.h"
#include "lwip/tcp.h"
-#include "lwip/tcp.h"
-#include "lwip/tcpip.h"
#include "netif/etharp.h"
/* Global variable containing MAC Config (hw addr, IP, GW, ...) */
@@ -223,6 +221,7 @@ void ethernet_task(void)
ethernet_timers_update();
}
+#if !LWIP_GMAC_TASK
/*
* \brief Sets the EMAC RX callback. It will be called when a new packet
* can be processed and should be called with a NULL parameter inside
@@ -234,6 +233,7 @@ void ethernet_set_rx_callback(gmac_dev_tx_cb_t callback)
{
ethernetif_set_rx_callback(callback);
}
+#endif
/*
* \brief Returns the current IP address
diff --git a/src/Networking/LwipEthernet/GMAC/ethernet_sam.h b/src/Networking/LwipEthernet/GMAC/ethernet_sam.h
index 0532dc88..23266cf3 100644
--- a/src/Networking/LwipEthernet/GMAC/ethernet_sam.h
+++ b/src/Networking/LwipEthernet/GMAC/ethernet_sam.h
@@ -72,11 +72,12 @@ void ethernet_timers_update(void);
// Reads all stored network packets and processes them
void ethernet_task(void);
+#if !LWIP_GMAC_TASK
// Set the RX callback for incoming network packets
void ethernet_set_rx_callback(gmac_dev_tx_cb_t callback);
+#endif
// Returns the network interface's current IPv4 address
void ethernet_get_ipaddress(IPAddress& ipAddress, IPAddress& netMask, IPAddress& gateWay);
-
#endif /* ETHERNET_SAM_H_INCLUDED */
diff --git a/src/Networking/LwipEthernet/GMAC/same70_gmac.cpp b/src/Networking/LwipEthernet/GMAC/same70_gmac.cpp
index 12f070c8..895f7d22 100644
--- a/src/Networking/LwipEthernet/GMAC/same70_gmac.cpp
+++ b/src/Networking/LwipEthernet/GMAC/same70_gmac.cpp
@@ -3,39 +3,29 @@
*
* \brief GMAC (Gigabit MAC) driver for lwIP.
*
- * Copyright (c) 2015-2016 Atmel Corporation. All rights reserved.
+ * Copyright (c) 2015-2018 Microchip Technology Inc. and its subsidiaries.
*
* \asf_license_start
*
* \page License
*
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions are met:
+ * Subject to your compliance with these terms, you may use Microchip
+ * software and any derivatives exclusively with Microchip products.
+ * It is your responsibility to comply with third party license terms applicable
+ * to your use of third party software (including open source software) that
+ * may accompany Microchip software.
*
- * 1. Redistributions of source code must retain the above copyright notice,
- * this list of conditions and the following disclaimer.
- *
- * 2. Redistributions in binary form must reproduce the above copyright notice,
- * this list of conditions and the following disclaimer in the documentation
- * and/or other materials provided with the distribution.
- *
- * 3. The name of Atmel may not be used to endorse or promote products derived
- * from this software without specific prior written permission.
- *
- * 4. This software may only be redistributed and used in connection with an
- * Atmel microcontroller product.
- *
- * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
- * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
- * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE
- * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL 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.
+ * THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS". NO WARRANTIES,
+ * WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
+ * INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
+ * AND FITNESS FOR A PARTICULAR PURPOSE. IN NO EVENT WILL MICROCHIP BE
+ * LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE, INCIDENTAL OR CONSEQUENTIAL
+ * LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND WHATSOEVER RELATED TO THE
+ * SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS BEEN ADVISED OF THE
+ * POSSIBILITY OR THE DAMAGES ARE FORESEEABLE. TO THE FULLEST EXTENT
+ * ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL CLAIMS IN ANY WAY
+ * RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF FEES, IF ANY,
+ * THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
*
* \asf_license_stop
*
@@ -48,29 +38,40 @@
extern "C" {
#include "ethernet_phy.h"
+#include "lwip/opt.h"
+#include "lwip/sys.h"
#include "lwip/def.h"
#include "lwip/mem.h"
-#include "lwip/opt.h"
#include "lwip/pbuf.h"
-#include "lwip/snmp.h"
#include "lwip/stats.h"
-#include "lwip/sys.h"
+#include "lwip/snmp.h"
#include "netif/etharp.h"
}
#define __nocache __attribute__((section(".ram_nocache")))
+extern void delay(uint32_t ms);
+
#if LWIP_GMAC_TASK
// We can't #include RepRapFirmware.h here because that leads to a duplicate definition of ERR_TIMEOUT
#include <RTOSIface/RTOSIface.h>
#include <TaskPriorities.h>
-constexpr size_t EthernetTaskStackWords = 200;
+extern Mutex lwipMutex;
+
+constexpr size_t EthernetTaskStackWords = 250;
static Task<EthernetTaskStackWords> ethernetTask;
#endif
+// Error counters
+unsigned int rxErrorCount;
+unsigned int rxBuffersNotFullyPopulatedCount;
+unsigned int txErrorCount;
+unsigned int txBufferNotFreeCount;
+unsigned int txBufferTooShortCount;
+
/** Network interface identifier. */
#define IFNAME0 'e'
#define IFNAME1 'n'
@@ -123,9 +124,9 @@ struct gmac_device {
* of the address shall be set to 0.
*/
/** Pointer to Rx descriptor list (must be 8-byte aligned). */
- gmac_rx_descriptor_t rx_desc[GMAC_RX_BUFFERS];
+ volatile gmac_rx_descriptor_t rx_desc[GMAC_RX_BUFFERS];
/** Pointer to Tx descriptor list (must be 8-byte aligned). */
- gmac_tx_descriptor_t tx_desc[GMAC_TX_BUFFERS];
+ volatile gmac_tx_descriptor_t tx_desc[GMAC_TX_BUFFERS];
/** RX pbuf pointer list. */
struct pbuf *rx_pbuf[GMAC_RX_BUFFERS];
/** TX buffers. */
@@ -158,6 +159,8 @@ static uint8_t gs_uc_mac_address[] =
ETHERNET_CONF_ETHADDR5
};
+static bool rxPbufsFullyPopulated = false;
+
#if LWIP_STATS
/** Used to compute lwIP bandwidth. */
uint32_t lwip_tx_count = 0;
@@ -166,7 +169,9 @@ uint32_t lwip_tx_rate = 0;
uint32_t lwip_rx_rate = 0;
#endif
-static gmac_dev_tx_cb_t gmac_rx_cb = NULL;
+#if !LWIP_GMAC_TASK
+static gmac_dev_tx_cb_t gmac_rx_cb = nullptr;
+#endif
/**
* \brief GMAC interrupt handler.
@@ -190,7 +195,7 @@ void GMAC_Handler(void)
ul_isr = gmac_get_interrupt_status(GMAC);
/* RX interrupts. */
- if ((ul_isr & GMAC_INT_GROUP) != 0 && gmac_rx_cb != NULL)
+ if ((ul_isr & GMAC_INT_GROUP) != 0 && gmac_rx_cb != nullptr)
{
gmac_rx_cb(ul_isr);
}
@@ -207,21 +212,25 @@ void GMAC_Handler(void)
* (since the lsb are used as status bits by GMAC).
*
* \param p_gmac_dev Pointer to driver data structure.
+ * \param startAt The index to start populating from
*/
-static void gmac_rx_populate_queue(struct gmac_device *p_gmac_dev)
+static void gmac_rx_populate_queue(struct gmac_device *p_gmac_dev, uint32_t startAt)
{
- uint32_t ul_index = 0;
- struct pbuf *p = 0;
+ uint32_t ul_index = startAt;
/* Set up the RX descriptors. */
- for (ul_index = 0; ul_index < GMAC_RX_BUFFERS; ul_index++) {
- if (p_gmac_dev->rx_pbuf[ul_index] == 0) {
-
+ do
+ {
+ if (p_gmac_dev->rx_pbuf[ul_index] == nullptr)
+ {
/* Allocate a new pbuf with the maximum size. */
- p = pbuf_alloc(PBUF_RAW, (u16_t) GMAC_FRAME_LENTGH_MAX, PBUF_POOL);
- if (p == NULL) {
+ pbuf * const p = pbuf_alloc(PBUF_RAW, (u16_t) GMAC_FRAME_LENTGH_MAX, PBUF_POOL);
+ if (p == nullptr)
+ {
LWIP_DEBUGF(NETIF_DEBUG, ("gmac_rx_populate_queue: pbuf allocation failure\n"));
- break;
+ rxPbufsFullyPopulated = false;
+ ++rxBuffersNotFullyPopulatedCount;
+ return;
}
/* Make sure lwIP is well configured so one pbuf can contain the maximum packet size. */
@@ -231,22 +240,35 @@ static void gmac_rx_populate_queue(struct gmac_device *p_gmac_dev)
LWIP_ASSERT("gmac_rx_populate_queue: unaligned p->payload buffer address",
(((uint32_t)p->payload & 0xFFFFFFFC) == (uint32_t)p->payload));
- if (ul_index == GMAC_RX_BUFFERS - 1)
- p_gmac_dev->rx_desc[ul_index].addr.val = (u32_t) p->payload | GMAC_RXD_WRAP;
- else
- p_gmac_dev->rx_desc[ul_index].addr.val = (u32_t) p->payload;
-
+ // dc42 do this first to avoid a race condition with DMA, because writing addr.val transfers ownership back to the GMAC, so it should be the last thing we do
/* Reset status value. */
p_gmac_dev->rx_desc[ul_index].status.val = 0;
/* Save pbuf pointer to be sent to lwIP upper layer. */
p_gmac_dev->rx_pbuf[ul_index] = p;
+ if (ul_index == GMAC_RX_BUFFERS - 1)
+ {
+ p_gmac_dev->rx_desc[ul_index].addr.val = (u32_t) p->payload | GMAC_RXD_WRAP;
+ }
+ else
+ {
+ p_gmac_dev->rx_desc[ul_index].addr.val = (u32_t) p->payload;
+ }
+
LWIP_DEBUGF(NETIF_DEBUG,
("gmac_rx_populate_queue: new pbuf allocated: %p [idx=%u]\n",
p, ul_index));
}
- }
+
+ ++ul_index;
+ if (ul_index == GMAC_RX_BUFFERS)
+ {
+ ul_index = 0;
+ }
+ } while (ul_index != startAt);
+
+ rxPbufsFullyPopulated = true;
}
/**
@@ -264,15 +286,16 @@ static void gmac_rx_init(struct gmac_device *ps_gmac_dev)
ps_gmac_dev->us_rx_idx = 0;
/* Set up the RX descriptors. */
- for (ul_index = 0; ul_index < GMAC_RX_BUFFERS; ul_index++) {
- ps_gmac_dev->rx_pbuf[ul_index] = 0;
- ps_gmac_dev->rx_desc[ul_index].addr.val = 0;
+ for (ul_index = 0; ul_index < GMAC_RX_BUFFERS; ul_index++)
+ {
+ ps_gmac_dev->rx_pbuf[ul_index] = nullptr;
+ ps_gmac_dev->rx_desc[ul_index].addr.val = GMAC_RXD_OWNERSHIP; // mark it as not free for hardware to use, until we have allocated the pbuf
ps_gmac_dev->rx_desc[ul_index].status.val = 0;
}
ps_gmac_dev->rx_desc[ul_index - 1].addr.val |= GMAC_RXD_WRAP;
/* Build RX buffer and descriptors. */
- gmac_rx_populate_queue(ps_gmac_dev);
+ gmac_rx_populate_queue(ps_gmac_dev, 0);
/* Set receive buffer queue base address pointer. */
gmac_set_rx_queue(GMAC, (uint32_t) &ps_gmac_dev->rx_desc[0]);
@@ -293,8 +316,9 @@ static void gmac_tx_init(struct gmac_device *ps_gmac_dev)
ps_gmac_dev->us_tx_idx = 0;
/* Set up the TX descriptors. */
- for (ul_index = 0; ul_index < GMAC_TX_BUFFERS; ul_index++) {
- ps_gmac_dev->tx_desc[ul_index].addr = (uint32_t)&ps_gmac_dev->tx_buf[ul_index][0];
+ for (ul_index = 0; ul_index < GMAC_TX_BUFFERS; ul_index++)
+ {
+ ps_gmac_dev->tx_desc[ul_index].addr = reinterpret_cast<uint32_t>(&ps_gmac_dev->tx_buf[ul_index][0]);
ps_gmac_dev->tx_desc[ul_index].status.val = GMAC_TXD_USED | GMAC_TXD_LAST;
}
ps_gmac_dev->tx_desc[ul_index - 1].status.val |= GMAC_TXD_WRAP;
@@ -378,14 +402,14 @@ static void gmac_low_level_init(struct netif *netif)
* \return ERR_OK if the packet could be sent.
* an err_t value if the packet couldn't be sent.
*/
-static err_t gmac_low_level_output(struct netif *netif, struct pbuf *p)
+static err_t gmac_low_level_output(netif *p_netif, struct pbuf *p)
{
- struct gmac_device *ps_gmac_dev = static_cast<gmac_device *>(netif->state);
- struct pbuf *q = NULL;
- uint8_t *buffer = 0;
+ gmac_device *const ps_gmac_dev = static_cast<gmac_device *>(p_netif->state);
/* Handle GMAC underrun or AHB errors. */
- if (gmac_get_tx_status(GMAC) & GMAC_TX_ERRORS) {
+ if (gmac_get_tx_status(GMAC) & GMAC_TX_ERRORS)
+ {
+ ++txErrorCount;
LWIP_DEBUGF(NETIF_DEBUG, ("gmac_low_level_output: GMAC ERROR, reinit TX...\n"));
gmac_enable_transmit(GMAC, false);
@@ -402,20 +426,36 @@ static err_t gmac_low_level_output(struct netif *netif, struct pbuf *p)
gmac_enable_transmit(GMAC, true);
}
- //TODO check buffer is free!!!
- //TODO what if message is too long?
-
- buffer = (uint8_t*)ps_gmac_dev->tx_desc[ps_gmac_dev->us_tx_idx].addr;
+ while ((ps_gmac_dev->tx_desc[ps_gmac_dev->us_tx_idx].status.val & GMAC_TXD_USED) == 0)
+ {
+ ++txBufferNotFreeCount;
+ delay(1);
+ }
- /* Copy pbuf chain into TX buffer. */
- for (q = p; q != NULL; q = q->next) {
- memcpy(buffer, q->payload, q->len);
- buffer += q->len;
+ // Copy pbuf chain into TX buffer
+ {
+ uint8_t *buffer = reinterpret_cast<uint8_t*>(ps_gmac_dev->tx_desc[ps_gmac_dev->us_tx_idx].addr);
+ size_t totalLength = 0;
+ for (const pbuf *q = p; q != NULL; q = q->next)
+ {
+ totalLength += q->len;
+ if (totalLength > GMAC_TX_UNITSIZE)
+ {
+ ++txBufferTooShortCount;
+ return ERR_BUF;
+ }
+ memcpy(buffer, q->payload, q->len);
+ buffer += q->len;
+ }
}
- /* Set len and mark the buffer to be sent by GMAC. */
- ps_gmac_dev->tx_desc[ps_gmac_dev->us_tx_idx].status.bm.b_len = p->tot_len;
- ps_gmac_dev->tx_desc[ps_gmac_dev->us_tx_idx].status.bm.b_used = 0;
+ // Set length and mark the buffer to be sent by GMAC
+ uint32_t txStat = p->tot_len | GMAC_TXD_LAST;
+ if (ps_gmac_dev->us_tx_idx == GMAC_TX_BUFFERS - 1)
+ {
+ txStat |= GMAC_TXD_WRAP;
+ }
+ ps_gmac_dev->tx_desc[ps_gmac_dev->us_tx_idx].status.val = txStat;
LWIP_DEBUGF(NETIF_DEBUG,
("gmac_low_level_output: DMA buffer sent, size=%d [idx=%u]\n",
@@ -442,50 +482,56 @@ static err_t gmac_low_level_output(struct netif *netif, struct pbuf *p)
* \return a pbuf filled with the received packet (including MAC header).
* 0 on memory error.
*/
-static struct pbuf *gmac_low_level_input(struct netif *netif)
+static pbuf *gmac_low_level_input(struct netif *netif)
{
- struct gmac_device *ps_gmac_dev = static_cast<gmac_device *>(netif->state);
- struct pbuf *p = 0;
- uint32_t length = 0;
- uint32_t ul_index = 0;
- gmac_rx_descriptor_t *p_rx = &ps_gmac_dev->rx_desc[ps_gmac_dev->us_rx_idx];
-
- /* Handle GMAC overrun or AHB errors. */
- if (gmac_get_rx_status(GMAC) & GMAC_RX_ERRORS) {
+ gmac_device *ps_gmac_dev = static_cast<gmac_device *>(netif->state);
+ if (gmac_get_rx_status(GMAC) & GMAC_RX_ERRORS)
+ {
+ // Handle GMAC overrun or AHB errors
+ ++rxErrorCount;
gmac_enable_receive(GMAC, false);
LINK_STATS_INC(link.err);
LINK_STATS_INC(link.drop);
/* Free all RX pbufs. */
- for (ul_index = 0; ul_index < GMAC_RX_BUFFERS; ul_index++) {
- if (ps_gmac_dev->rx_pbuf[ul_index] != 0) {
+ for (uint32_t ul_index = 0; ul_index < GMAC_RX_BUFFERS; ul_index++)
+ {
+ if (ps_gmac_dev->rx_pbuf[ul_index] != 0)
+ {
pbuf_free(ps_gmac_dev->rx_pbuf[ul_index]);
- ps_gmac_dev->rx_pbuf[ul_index] = 0;
+ ps_gmac_dev->rx_pbuf[ul_index] = nullptr;
}
}
- /* Reinit TX descriptors. */
+ /* Reinit RX descriptors. */
gmac_rx_init(ps_gmac_dev);
/* Clear error status. */
gmac_clear_rx_status(GMAC, GMAC_RX_ERRORS);
gmac_enable_receive(GMAC, true);
+ return nullptr;
}
- /* Check that a packet has been received and processed by GMAC. */
- if ((p_rx->addr.val & GMAC_RXD_OWNERSHIP) == GMAC_RXD_OWNERSHIP) {
+ volatile gmac_rx_descriptor_t * const p_rx = &ps_gmac_dev->rx_desc[ps_gmac_dev->us_rx_idx];
+ pbuf * const p = ((p_rx->addr.val & GMAC_RXD_OWNERSHIP) == GMAC_RXD_OWNERSHIP)
+ ? ps_gmac_dev->rx_pbuf[ps_gmac_dev->us_rx_idx]
+ : nullptr;
+
+ /* Check if a packet has been received and processed by GMAC. */
+ if (p != nullptr)
+ {
/* Packet is a SOF since packet size is set to maximum. */
- length = p_rx->status.val & GMAC_RXD_LEN_MASK;
+ const uint32_t length = p_rx->status.val & GMAC_RXD_LEN_MASK;
/* Fetch pre-allocated pbuf. */
- p = ps_gmac_dev->rx_pbuf[ps_gmac_dev->us_rx_idx];
p->len = length;
- /* Remove this pbuf from its desriptor. */
- ps_gmac_dev->rx_pbuf[ps_gmac_dev->us_rx_idx] = 0;
+ /* Remove this pbuf from its descriptor. */
+ ps_gmac_dev->rx_pbuf[ps_gmac_dev->us_rx_idx] = nullptr;
+ rxPbufsFullyPopulated = false;
LWIP_DEBUGF(NETIF_DEBUG,
("gmac_low_level_input: DMA buffer %p received, size=%u [idx=%u]\n",
@@ -495,12 +541,6 @@ static struct pbuf *gmac_low_level_input(struct netif *netif)
p->tot_len = length;
LINK_STATS_INC(link.recv);
- /* Fill empty descriptors with new pbufs. */
- gmac_rx_populate_queue(ps_gmac_dev);
-
- /* Mark the descriptor ready for transfer. */
- p_rx->addr.val &= ~(GMAC_RXD_OWNERSHIP);
-
ps_gmac_dev->us_rx_idx = (ps_gmac_dev->us_rx_idx + 1) % GMAC_RX_BUFFERS;
#if LWIP_STATS
@@ -508,6 +548,12 @@ static struct pbuf *gmac_low_level_input(struct netif *netif)
#endif
}
+ /* Fill empty descriptors with new pbufs. */
+ if (!rxPbufsFullyPopulated)
+ {
+ gmac_rx_populate_queue(ps_gmac_dev, ps_gmac_dev->us_rx_idx);
+ }
+
return p;
}
@@ -519,16 +565,21 @@ static struct pbuf *gmac_low_level_input(struct netif *netif)
*
* \param pvParameters A pointer to the gmac_device instance.
*/
-extern "C" void gmac_task(void *pvParameters)
+extern "C" [[noreturn]] void gmac_task(void *pvParameters)
{
gmac_device * const ps_gmac_dev = static_cast<gmac_device*>(pvParameters);
+ netif * const p_netif = ps_gmac_dev->netif;
- while (1) {
- /* Process the incoming packets */
- while (ethernetif_input(ps_gmac_dev->netif)) { }
+ while (1)
+ {
+ // Process the incoming packets
+ {
+ MutexLocker lock(lwipMutex);
+ while (ethernetif_input(p_netif)) { }
+ }
- /* Wait for the RX notification from the ISR */
- TaskBase::Take();
+ // Wait for the RX notification from the ISR
+ TaskBase::Take((rxPbufsFullyPopulated) ? 1000 : 20);
}
}
#endif
@@ -549,7 +600,7 @@ bool ethernetif_input(struct netif *netif)
/* Move received packet into a new pbuf. */
p = gmac_low_level_input(netif);
- if (p == NULL)
+ if (p == nullptr)
{
return false;
}
@@ -760,10 +811,12 @@ bool ethernetif_link_established(void)
return true;
}
+#if !LWIP_GMAC_TASK
void ethernetif_set_rx_callback(gmac_dev_tx_cb_t callback)
{
gmac_rx_cb = callback;
}
+#endif
void ethernetif_set_mac_address(const uint8_t macAddress[])
{
@@ -777,7 +830,7 @@ void ethernetif_set_mac_address(const uint8_t macAddress[])
extern "C" u32_t millis();
-u32_t sys_now(void)
+extern "C" u32_t sys_now(void)
{
return millis();
}
diff --git a/src/Networking/LwipEthernet/GMAC/same70_gmac.h b/src/Networking/LwipEthernet/GMAC/same70_gmac.h
index fe263623..7c676ff7 100644
--- a/src/Networking/LwipEthernet/GMAC/same70_gmac.h
+++ b/src/Networking/LwipEthernet/GMAC/same70_gmac.h
@@ -67,8 +67,10 @@ bool ethernetif_establish_link(void); // attempts to establish link and retu
bool ethernetif_link_established(void); // asks the PHY if the link is still up
+#if !LWIP_GMAC_TASK
typedef void (*gmac_dev_tx_cb_t) (uint32_t ul_status); // copied from gmac_raw.h
void ethernetif_set_rx_callback(gmac_dev_tx_cb_t callback);
+#endif
void ethernetif_set_mac_address(const uint8_t macAddress[]);
@@ -78,4 +80,11 @@ void ethernetif_set_mac_address(const uint8_t macAddress[]);
}
#endif
+// Error counters
+extern unsigned int rxErrorCount;
+extern unsigned int rxBuffersNotFullyPopulatedCount;
+extern unsigned int txErrorCount;
+extern unsigned int txBufferNotFreeCount;
+extern unsigned int txBufferTooShortCount;
+
#endif /* ETHERNETIF_H_INCLUDED */
diff --git a/src/Networking/LwipEthernet/Lwip/lwipopts.h b/src/Networking/LwipEthernet/Lwip/lwipopts.h
index 367f37c8..c2c683c6 100644
--- a/src/Networking/LwipEthernet/Lwip/lwipopts.h
+++ b/src/Networking/LwipEthernet/Lwip/lwipopts.h
@@ -56,11 +56,8 @@
* use lwIP facilities.
* Uses Raw API only.
*/
-#ifndef LWIP_GMAC_TASK
-# error LWIP_GMAC_TASK must be defined in compiler settings
-#endif
-#define NO_SYS (!LWIP_GMAC_TASK)
+#define NO_SYS 1
/**
* LWIP_NETIF_STATUS_CALLBACK==1: Support a callback function whenever an interface
@@ -136,7 +133,7 @@
* MEMP_NUM_REASSDATA: the number of IP packets simultaneously queued for
* reassembly (whole packets, not fragments!)
*/
-#define MEMP_NUM_REASSDATA 2
+#define MEMP_NUM_REASSDATA 5
/**
* MEMP_NUM_FRAG_PBUF: the number of IP fragments simultaneously sent
@@ -167,9 +164,9 @@
#define MEMP_NUM_NETCONN 0
/**
- * PBUF_POOL_SIZE: the number of buffers in the pbuf pool.
+ * PBUF_POOL_SIZE: the number of buffers in the pbuf pool. Needs to be enough for IP packet reassembly.
*/
-#define PBUF_POOL_SIZE (GMAC_RX_BUFFERS + 4)
+#define PBUF_POOL_SIZE (GMAC_RX_BUFFERS + GMAC_TX_BUFFERS + 12)
/**
* PBUF_POOL_BUFSIZE: the size of each pbuf in the pbuf pool.
diff --git a/src/Networking/LwipEthernet/LwipEthernetInterface.cpp b/src/Networking/LwipEthernet/LwipEthernetInterface.cpp
index c9e14533..f32bf251 100644
--- a/src/Networking/LwipEthernet/LwipEthernetInterface.cpp
+++ b/src/Networking/LwipEthernet/LwipEthernetInterface.cpp
@@ -46,86 +46,91 @@ const unsigned int MdnsTtl = 10 * 60; // same value as on the Duet 0.6/0.8.5
static LwipEthernetInterface *ethernetInterface;
-extern "C"
-{
-static volatile bool lwipLocked = false;
+#if LWIP_GMAC_TASK
+
+# include <RTOSIface/RTOSIface.h>
+Mutex lwipMutex;
-#if !LWIP_GMAC_TASK
-static volatile bool resetCallback = false;
#endif
-// Lock functions for LwIP (LwIP isn't thread-safe when working with the raw API)
-bool LockLWIP()
+extern "C"
{
- if (lwipLocked)
- {
- return false;
- }
- lwipLocked = true;
- return true;
-}
+#if !LWIP_GMAC_TASK
-void UnlockLWIP()
-{
- lwipLocked = false;
-}
+ static volatile bool lwipLocked = false;
+ static volatile bool resetCallback = false;
-// Callback functions for the GMAC driver and for LwIP
+ // Lock functions for LwIP (LwIP isn't thread-safe when working with the raw API)
+ bool LockLWIP()
+ {
+ if (lwipLocked)
+ {
+ return false;
+ }
-#if !LWIP_GMAC_TASK
+ lwipLocked = true;
+ return true;
+ }
-// Called from ISR
-static void ethernet_rx_callback(uint32_t ul_status)
-{
- // Because the LWIP stack can become corrupted if we work with it in parallel,
- // we may have to wait for the next Spin() call to read the next packet.
- if (LockLWIP())
+ void UnlockLWIP()
{
- ethernet_task();
- UnlockLWIP();
+ lwipLocked = false;
}
- else
+
+ // Callback functions for the GMAC driver and for LwIP
+
+ // Called from ISR
+ static void ethernet_rx_callback(uint32_t ul_status)
{
- ethernet_set_rx_callback(nullptr);
- resetCallback = true;
+ // Because the LWIP stack can become corrupted if we work with it in parallel,
+ // we may have to wait for the next Spin() call to read the next packet.
+ if (LockLWIP())
+ {
+ ethernet_task();
+ UnlockLWIP();
+ }
+ else
+ {
+ ethernet_set_rx_callback(nullptr);
+ resetCallback = true;
+ }
}
-}
-#endif
+ #endif
-// Task function to keep the GMAC and LwIP running
-void DoEthernetTask()
-{
- ethernet_task();
+ // Task function to keep the GMAC and LwIP running
+ void DoEthernetTask()
+ {
+ ethernet_task();
#if !LWIP_GMAC_TASK
- if (resetCallback)
- {
- resetCallback = false;
- ethernet_set_rx_callback(&ethernet_rx_callback);
- }
+ if (resetCallback)
+ {
+ resetCallback = false;
+ ethernet_set_rx_callback(&ethernet_rx_callback);
+ }
#endif
-}
+ }
-// Callback functions for LWIP (may be called from ISR)
+ // Callback functions for LWIP (may be called from ISR)
-static err_t conn_accept(void *arg, tcp_pcb *pcb, err_t err)
-{
- LWIP_UNUSED_ARG(arg);
- LWIP_UNUSED_ARG(err);
-
- if (ethernetInterface->ConnectionEstablished(pcb))
+ static err_t conn_accept(void *arg, tcp_pcb *pcb, err_t err)
{
- // A socket has accepted this connection and will deal with it
- return ERR_OK;
- }
+ LWIP_UNUSED_ARG(arg);
+ LWIP_UNUSED_ARG(err);
- tcp_abort(pcb);
- return ERR_ABRT;
-}
+ if (ethernetInterface->ConnectionEstablished(pcb))
+ {
+ // A socket has accepted this connection and will deal with it
+ return ERR_OK;
+ }
-}
+ tcp_abort(pcb);
+ return ERR_ABRT;
+ }
+
+} // end extern "C"
/*-----------------------------------------------------------------------------------*/
@@ -172,9 +177,13 @@ DEFINE_GET_OBJECT_MODEL_TABLE(LwipEthernetInterface)
void LwipEthernetInterface::Init()
{
- interfaceMutex.Create("Lwip");
+ interfaceMutex.Create("LwipIface");
//TODO we don't yet use this mutex anywhere!
+#if LWIP_GMAC_TASK
+ lwipMutex.Create("LwipCore");
+#endif
+
// Clear the PCBs
for (size_t i = 0; i < NumTcpPorts; ++i)
{
@@ -368,7 +377,7 @@ GCodeResult LwipEthernetInterface::GetNetworkState(const StringRef& reply)
void LwipEthernetInterface::Start()
{
#if defined(DUET3)
- digitalWrite(PhyResetPin, true); // being the Ethernet Phy out of reset
+ digitalWrite(PhyResetPin, true); // bring the Ethernet Phy out of reset
#endif
if (initialised)
@@ -409,8 +418,8 @@ void LwipEthernetInterface::Stop()
netif_set_down(&gs_net_if);
#if !LWIP_GMAC_TASK
resetCallback = false;
-#endif
ethernet_set_rx_callback(nullptr);
+#endif
#if defined(DUET3)
pinMode(PhyResetPin, OUTPUT_LOW); // hold the Ethernet Phy chip in reset
@@ -420,10 +429,14 @@ void LwipEthernetInterface::Stop()
}
// Main spin loop. If 'full' is true then we are being called from the main spin loop. If false then we are being called during HSMCI idle time.
-void LwipEthernetInterface::Spin(bool full)
+void LwipEthernetInterface::Spin()
{
+#if LWIP_GMAC_TASK
+ MutexLocker lock(lwipMutex);
+#else
if (LockLWIP()) // basically we can't do anything if we can't interact with LWIP
{
+#endif
switch(state)
{
case NetworkState::enabled:
@@ -456,28 +469,25 @@ void LwipEthernetInterface::Spin(bool full)
break;
case NetworkState::obtainingIP:
- if (full)
+ if (ethernet_link_established())
{
- if (ethernet_link_established())
+ // Check for incoming packets
+ DoEthernetTask();
+
+ // Have we obtained an IP address yet?
+ ethernet_get_ipaddress(ipAddress, netmask, gateway);
+ if (!ipAddress.IsNull())
{
- // Check for incoming packets
- DoEthernetTask();
-
- // Have we obtained an IP address yet?
- ethernet_get_ipaddress(ipAddress, netmask, gateway);
- if (!ipAddress.IsNull())
- {
- // Notify the mDNS responder about this
- state = NetworkState::connected;
+ // Notify the mDNS responder about this
+ state = NetworkState::connected;
// debugPrintf("IP address obtained, network running\n");
- }
}
- else
- {
+ }
+ else
+ {
// debugPrintf("Lost phy link\n");
- TerminateSockets();
- state = NetworkState::establishingLink;
- }
+ TerminateSockets();
+ state = NetworkState::establishingLink;
}
break;
@@ -487,14 +497,11 @@ void LwipEthernetInterface::Spin(bool full)
dhcp_stop(&gs_net_if);
}
- if (full)
- {
- InitSockets();
- RebuildMdnsServices();
- ethernet_get_ipaddress(ipAddress, netmask, gateway);
- platform.MessageF(NetworkInfoMessage, "Ethernet running, IP address = %s\n", IP4String(ipAddress).c_str());
- state = NetworkState::active;
- }
+ InitSockets();
+ RebuildMdnsServices();
+ ethernet_get_ipaddress(ipAddress, netmask, gateway);
+ platform.MessageF(NetworkInfoMessage, "Ethernet running, IP address = %s\n", IP4String(ipAddress).c_str());
+ state = NetworkState::active;
break;
case NetworkState::active:
@@ -505,7 +512,7 @@ void LwipEthernetInterface::Spin(bool full)
DoEthernetTask();
// Poll the next TCP socket
- sockets[nextSocketToPoll]->Poll(full);
+ sockets[nextSocketToPoll]->Poll();
// Move on to the next TCP socket for next time
++nextSocketToPoll;
@@ -520,7 +527,7 @@ void LwipEthernetInterface::Spin(bool full)
TerminateDataPort();
}
}
- else if (full)
+ else
{
// debugPrintf("Lost phy link\n");
TerminateSockets();
@@ -528,8 +535,10 @@ void LwipEthernetInterface::Spin(bool full)
}
break;
}
+#if !LWIP_GMAC_TASK
UnlockLWIP();
}
+#endif
}
void LwipEthernetInterface::Interrupt()
@@ -547,6 +556,7 @@ void LwipEthernetInterface::Diagnostics(MessageType mtype)
{
platform.Message(mtype, "- Ethernet -\n");
platform.MessageF(mtype, "State: %d\n", (int)state);
+ platform.MessageF(mtype, "Error counts: %u %u %u %u %u\n", rxErrorCount, rxBuffersNotFullyPopulatedCount, txErrorCount, txBufferNotFreeCount, txBufferTooShortCount);
platform.Message(mtype, "Socket states:");
for (LwipSocket *s : sockets)
{
@@ -594,7 +604,11 @@ int LwipEthernetInterface::EnableState() const
bool LwipEthernetInterface::InNetworkStack() const
{
+#if LWIP_GMAC_TASK
+ return false;
+#else
return lwipLocked;
+#endif
}
bool LwipEthernetInterface::ConnectionEstablished(tcp_pcb *pcb)
diff --git a/src/Networking/LwipEthernet/LwipEthernetInterface.h b/src/Networking/LwipEthernet/LwipEthernetInterface.h
index 7eacbc29..94ec30e0 100644
--- a/src/Networking/LwipEthernet/LwipEthernetInterface.h
+++ b/src/Networking/LwipEthernet/LwipEthernetInterface.h
@@ -33,7 +33,7 @@ public:
void Init() override;
void Activate() override;
void Exit() override;
- void Spin(bool full) override;
+ void Spin() override;
void Interrupt() override;
void Diagnostics(MessageType mtype) override;
diff --git a/src/Networking/LwipEthernet/LwipSocket.cpp b/src/Networking/LwipEthernet/LwipSocket.cpp
index 786a2db0..69d7bab5 100644
--- a/src/Networking/LwipEthernet/LwipSocket.cpp
+++ b/src/Networking/LwipEthernet/LwipSocket.cpp
@@ -12,6 +12,9 @@
#include "Networking/NetworkBuffer.h"
#include "RepRap.h"
+#if LWIP_GMAC_TASK
+extern Mutex lwipMutex;
+#endif
//***************************************************************************************************
@@ -63,8 +66,10 @@ static err_t conn_sent(void *arg, tcp_pcb *pcb, u16_t len)
return ERR_OK;
}
+#if !LWIP_GMAC_TASK
extern bool LockLWIP();
extern void UnlockLWIP();
+#endif
}
@@ -203,6 +208,9 @@ void LwipSocket::Close()
{
if (state != SocketState::disabled && state != SocketState::listening)
{
+#if LWIP_GMAC_TASK
+ MutexLocker lock(lwipMutex);
+#endif
DiscardReceivedData();
state = SocketState::closing;
whenClosed = millis();
@@ -219,6 +227,9 @@ void LwipSocket::Terminate()
{
if (state != SocketState::disabled)
{
+#if LWIP_GMAC_TASK
+ MutexLocker lock(lwipMutex);
+#endif
if (connectionPcb != nullptr)
{
tcp_err(connectionPcb, nullptr);
@@ -251,11 +262,14 @@ bool LwipSocket::ReadChar(char& c)
{
if (receivedData != nullptr)
{
- const char *data = (char *)receivedData->payload;
+ const char * const data = (const char *)receivedData->payload;
c = data[readIndex++];
if (readIndex >= receivedData->len)
{
+#if LWIP_GMAC_TASK
+ MutexLocker lock(lwipMutex);
+#endif
// We've processed one more pbuf
if (connectionPcb != nullptr)
{
@@ -282,7 +296,7 @@ bool LwipSocket::ReadBuffer(const uint8_t *&buffer, size_t &len)
{
if (receivedData != nullptr)
{
- const uint8_t *data = (const uint8_t *)receivedData->payload;
+ const uint8_t * const data = (const uint8_t *)receivedData->payload;
buffer = &data[readIndex];
len = receivedData->len - readIndex;
return true;
@@ -299,6 +313,9 @@ void LwipSocket::Taken(size_t len)
readIndex += len;
if (readIndex >= receivedData->len)
{
+#if LWIP_GMAC_TASK
+ MutexLocker lock(lwipMutex);
+#endif
// Notify LwIP
if (connectionPcb != nullptr)
{
@@ -316,7 +333,7 @@ void LwipSocket::Taken(size_t len)
}
// Poll a socket to see if it needs to be serviced
-void LwipSocket::Poll(bool full)
+void LwipSocket::Poll()
{
switch (state)
{
@@ -327,27 +344,24 @@ void LwipSocket::Poll(bool full)
case SocketState::connected:
// A connection has been established, but no responder has been found yet
// See if we can assign this socket
- if (full)
+ if (responderFound)
{
- if (responderFound)
+ // Are we still waiting for data to be written?
+ if (whenWritten != 0 && millis() - whenWritten >= MaxWriteTime)
{
- // Are we still waiting for data to be written?
- if (whenWritten != 0 && millis() - whenWritten >= MaxWriteTime)
- {
- Terminate();
- }
+ Terminate();
}
- else
+ }
+ else
+ {
+ // Try to find a responder to deal with this connection
+ if (reprap.GetNetwork().FindResponder(this, protocol))
{
- // Try to find a responder to deal with this connection
- if (reprap.GetNetwork().FindResponder(this, protocol))
- {
- responderFound = true;
- }
- else if (millis() - whenConnected >= FindResponderTimeout)
- {
- Terminate();
- }
+ responderFound = true;
+ }
+ else if (millis() - whenConnected >= FindResponderTimeout)
+ {
+ Terminate();
}
}
break;
@@ -356,28 +370,25 @@ void LwipSocket::Poll(bool full)
case SocketState::closing:
// The connection is being closed, but we may be waiting for sent data to be ACKed
// or for the received data to be processed by a NetworkResponder
- if (full)
+ if (unAcked == 0 || millis() - whenClosed > MaxAckTime)
{
- if (unAcked == 0 || millis() - whenClosed > MaxAckTime)
+ if (connectionPcb != nullptr)
{
- if (connectionPcb != nullptr)
+ tcp_err(connectionPcb, nullptr);
+ tcp_recv(connectionPcb, nullptr);
+ tcp_sent(connectionPcb, nullptr);
+ if (unAcked == 0)
{
- tcp_err(connectionPcb, nullptr);
- tcp_recv(connectionPcb, nullptr);
- tcp_sent(connectionPcb, nullptr);
- if (unAcked == 0)
- {
- tcp_close(connectionPcb);
- }
- else
- {
- tcp_abort(connectionPcb);
- }
- connectionPcb = nullptr;
+ tcp_close(connectionPcb);
}
-
- state = (localPort == 0) ? SocketState::disabled : SocketState::listening;
+ else
+ {
+ tcp_abort(connectionPcb);
+ }
+ connectionPcb = nullptr;
}
+
+ state = (localPort == 0) ? SocketState::disabled : SocketState::listening;
}
break;
@@ -401,13 +412,19 @@ void LwipSocket::DiscardReceivedData()
// Send the data, returning the length buffered
size_t LwipSocket::Send(const uint8_t *data, size_t length)
{
+#if LWIP_GMAC_TASK
+ MutexLocker lock(lwipMutex);
+#else
// This is always called outside the EthernetInterface::Spin method. Wait for pending ISRs to finish
while (!LockLWIP()) { }
+#endif
if (!CanSend())
{
// Don't bother if we cannot send anything at all+
+#if !LWIP_GMAC_TASK
UnlockLWIP();
+#endif
return 0;
}
@@ -429,7 +446,9 @@ size_t LwipSocket::Send(const uint8_t *data, size_t length)
if (ERR_IS_FATAL(err))
{
Terminate();
+#if !LWIP_GMAC_TASK
UnlockLWIP();
+#endif
return 0;
}
else if (err == ERR_MEM)
@@ -438,7 +457,9 @@ size_t LwipSocket::Send(const uint8_t *data, size_t length)
{
// The buffers are full - try again later
tcp_output(connectionPcb);
+#if !LWIP_GMAC_TASK
UnlockLWIP();
+#endif
return 0;
}
bytesToSend /= 2;
@@ -450,7 +471,9 @@ size_t LwipSocket::Send(const uint8_t *data, size_t length)
if (ERR_IS_FATAL(tcp_output(connectionPcb)))
{
Terminate();
+#if !LWIP_GMAC_TASK
UnlockLWIP();
+#endif
return 0;
}
@@ -458,11 +481,15 @@ size_t LwipSocket::Send(const uint8_t *data, size_t length)
whenWritten = millis();
unAcked += bytesToSend;
+#if !LWIP_GMAC_TASK
UnlockLWIP();
+#endif
return bytesToSend;
}
+#if !LWIP_GMAC_TASK
UnlockLWIP();
+#endif
return 0;
}
diff --git a/src/Networking/LwipEthernet/LwipSocket.h b/src/Networking/LwipEthernet/LwipSocket.h
index 31c5d794..5f9b1f0f 100644
--- a/src/Networking/LwipEthernet/LwipSocket.h
+++ b/src/Networking/LwipEthernet/LwipSocket.h
@@ -34,7 +34,7 @@ public:
// Inherited members of the Socket class
void Init(SocketNumber s, Port serverPort, NetworkProtocol p);
void TerminateAndDisable() override;
- void Poll(bool full) override;
+ void Poll() override;
void Close() override;
bool IsClosing() const { return (state == SocketState::closing); }
void Terminate() override;