From e206087d6562322d28474bba6369946ea0266b02 Mon Sep 17 00:00:00 2001 From: Victor Arino Date: Tue, 6 Sep 2016 11:57:47 +0200 Subject: [PATCH 1/3] stm32_eth: Initial implementation by Victor Arino drivers/eth-phy: add generic Ethernet PHY iface cpu/stm32f4: implement eth driver peripheral This implements the ethernet (MAC) peripheral of the stm32f4 as a netdev driver. boards/stm32f4discovery: add eth configuration boards/stm32f4discovery: add feature stm32_eth tests/stm32_eth_lwip: add test application --- boards/stm32f4discovery/Makefile.features | 2 + boards/stm32f4discovery/include/periph_conf.h | 35 ++ cpu/stm32f4/include/periph_cpu.h | 116 ++++ cpu/stm32f4/periph/eth.c | 538 ++++++++++++++++++ drivers/include/net/phy.h | 134 +++++ tests/stm32_eth_lwip/Makefile | 17 + tests/stm32_eth_lwip/README.md | 21 + tests/stm32_eth_lwip/main.c | 85 +++ 8 files changed, 948 insertions(+) create mode 100644 cpu/stm32f4/periph/eth.c create mode 100644 drivers/include/net/phy.h create mode 100644 tests/stm32_eth_lwip/Makefile create mode 100644 tests/stm32_eth_lwip/README.md create mode 100644 tests/stm32_eth_lwip/main.c diff --git a/boards/stm32f4discovery/Makefile.features b/boards/stm32f4discovery/Makefile.features index fcdb12986960..5bff2bb9f418 100644 --- a/boards/stm32f4discovery/Makefile.features +++ b/boards/stm32f4discovery/Makefile.features @@ -1,10 +1,12 @@ # Put defined MCU peripherals here (in alphabetical order) FEATURES_PROVIDED += periph_adc FEATURES_PROVIDED += periph_dac +FEATURES_PROVIDED += periph_eth FEATURES_PROVIDED += periph_i2c FEATURES_PROVIDED += periph_pwm FEATURES_PROVIDED += periph_rtc FEATURES_PROVIDED += periph_spi +FEATURES_PROVIDED += periph_stm32_eth FEATURES_PROVIDED += periph_timer FEATURES_PROVIDED += periph_uart diff --git a/boards/stm32f4discovery/include/periph_conf.h b/boards/stm32f4discovery/include/periph_conf.h index e209748d014d..ad0a8600ca23 100644 --- a/boards/stm32f4discovery/include/periph_conf.h +++ b/boards/stm32f4discovery/include/periph_conf.h @@ -211,6 +211,41 @@ static const i2c_conf_t i2c_config[] = { #define I2C_NUMOF (sizeof(i2c_config) / sizeof(i2c_config[0])) /** @} */ +/** + * @name ETH configuration + * @{ + */ +#define ETH_NUMOF (1) +#define ETH_RX_BUFFER_COUNT (4) +#define ETH_TX_BUFFER_COUNT (4) + +#define ETH_RX_BUFFER_SIZE (1524) +#define ETH_TX_BUFFER_SIZE (1524) + +#define ETH_DMA_ISR isr_dma2_stream0 + +static const eth_conf_t eth_config = { + .mode = RMII, + .mac = { 1, 2, 3, 4, 5, 6 }, + .speed = ETH_SPEED_100TX_FD, + .dma_chan = 0, + .dma_stream = 8, + .phy_addr = 0x01, + .pins = { + GPIO_PIN(PORT_B, 12), + GPIO_PIN(PORT_B, 13), + GPIO_PIN(PORT_B, 11), + GPIO_PIN(PORT_C, 4), + GPIO_PIN(PORT_C, 5), + GPIO_PIN(PORT_A, 7), + GPIO_PIN(PORT_C, 1), + GPIO_PIN(PORT_A, 2), + GPIO_PIN(PORT_A, 1), + } +}; + +/** @} */ + #ifdef __cplusplus } #endif diff --git a/cpu/stm32f4/include/periph_cpu.h b/cpu/stm32f4/include/periph_cpu.h index 5faead9535bf..4a09f52970b6 100644 --- a/cpu/stm32f4/include/periph_cpu.h +++ b/cpu/stm32f4/include/periph_cpu.h @@ -84,6 +84,122 @@ typedef struct { uint8_t chan; /**< CPU ADC channel connected to the pin */ } adc_conf_t; +/** + * @brief Ethernet Peripheral configuration + */ +typedef struct { + enum { + MII = 18, /**< Configuration for MII */ + RMII = 9, /**< Configuration for RMII */ + SMI = 2, /**< Configuration for SMI */ + } mode; /**< Select configuration mode */ + enum { + ETH_SPEED_10T_HD = 0x0000, + ETH_SPEED_10T_FD = 0x0100, + ETH_SPEED_100TX_HD = 0x2000, + ETH_SPEED_100TX_FD = 0x2100, + } speed; /**< Speed selection */ + uint8_t dma_stream; /**< DMA stream used for TX */ + uint8_t dma_chan; /**< DMA channel used for TX */ + char mac[6]; /**< Et hernet MAC address */ + char phy_addr; /**< PHY address */ + gpio_t pins[]; /**< Pins to use. MII requires 18 pins, + RMII 9 and SMI 9. Not all speeds are + supported by all modes. */ +} eth_conf_t; + +/** + * @brief Power on the DMA device the given stream belongs to + * + * @param[in] stream logical DMA stream + */ +static inline void dma_poweron(int stream) +{ + if (stream < 8) { + periph_clk_en(AHB1, RCC_AHB1ENR_DMA1EN); + } + else { + periph_clk_en(AHB1, RCC_AHB1ENR_DMA2EN); + } +} + +/** + * @brief Get DMA base register + * + * For simplifying DMA stream handling, we map the DMA channels transparently to + * one integer number, such that DMA1 stream0 equals 0, DMA2 stream0 equals 8, + * DMA2 stream 7 equals 15 and so on. + * + * @param[in] stream logical DMA stream + */ +static inline DMA_TypeDef *dma_base(int stream) +{ + return (stream < 8) ? DMA1 : DMA2; +} + +/** + * @brief Get the DMA stream base address + * + * @param[in] stream logical DMA stream + * + * @return base address for the selected DMA stream + */ +static inline DMA_Stream_TypeDef *dma_stream(int stream) +{ + uint32_t base = (uint32_t)dma_base(stream); + + return (DMA_Stream_TypeDef *)(base + (0x10 + (0x18 * (stream & 0x7)))); +} + +/** + * @brief Select high or low DMA interrupt register based on stream number + * + * @param[in] stream logical DMA stream + * + * @return 0 for streams 0-3, 1 for streams 3-7 + */ +static inline int dma_hl(int stream) +{ + return ((stream & 0x4) >> 2); +} + +/** + * @brief Get the interrupt flag clear bit position in the DMA LIFCR register + * + * @param[in] stream logical DMA stream + */ +static inline uint32_t dma_ifc(int stream) +{ + switch (stream & 0x3) { + case 0: + return (1 << 5); + case 1: + return (1 << 11); + case 2: + return (1 << 21); + case 3: + return (1 << 27); + default: + return 0; + } +} + +static inline void dma_isr_enable(int stream) +{ + if (stream < 7) { + NVIC_EnableIRQ((IRQn_Type)((int)DMA1_Stream0_IRQn + stream)); + } + else if (stream == 7) { + NVIC_EnableIRQ(DMA1_Stream7_IRQn); + } + else if (stream < 13) { + NVIC_EnableIRQ((IRQn_Type)((int)DMA2_Stream0_IRQn + (stream - 8))); + } + else if (stream < 16) { + NVIC_EnableIRQ((IRQn_Type)((int)DMA2_Stream5_IRQn + (stream - 13))); + } +} + #ifdef __cplusplus } #endif diff --git a/cpu/stm32f4/periph/eth.c b/cpu/stm32f4/periph/eth.c new file mode 100644 index 000000000000..f336172f8ee9 --- /dev/null +++ b/cpu/stm32f4/periph/eth.c @@ -0,0 +1,538 @@ +/* + * Copyright (C) 2016 TriaGnoSys GmbH + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup cpu_stm32f4 + * @{ + * + * @file + * @brief Low-level ETH driver implementation + * + * @author Víctor Ariño + * + * @} + */ + +#include "cpu.h" +#include "mutex.h" +#include "assert.h" +#include "periph_conf.h" +#include "periph/gpio.h" + +#include "board.h" + +#include "net/netdev.h" +#include "net/netdev/eth.h" +#include "net/eui64.h" +#include "net/ethernet.h" +#include "net/netstats.h" +#include "net/phy.h" + +#define ENABLE_DEBUG (0) +#include "debug.h" + +#define SDEBUG(...) DEBUG("eth: " __VA_ARGS__) + +#include + +#if ETH_NUMOF + +/* Set the value of the divider with the clock configured */ +#if !defined(CLOCK_CORECLOCK) || CLOCK_CORECLOCK < (20000000U) +#error This peripheral requires a CORECLOCK of at least 20MHz +#elif CLOCK_CORECLOCK < (35000000U) +#define CLOCK_RANGE ETH_MACMIIAR_CR_Div16 +#elif CLOCK_CORECLOCK < (60000000U) +#define CLOCK_RANGE ETH_MACMIIAR_CR_Div26 +#elif CLOCK_CORECLOCK < (100000000U) +#define CLOCK_RANGE ETH_MACMIIAR_CR_Div42 +#elif CLOCK_CORECLOCK < (150000000U) +#define CLOCK_RANGE ETH_MACMIIAR_CR_Div62 +#else /* CLOCK_CORECLOCK < (20000000U) */ +#define CLOCK_RANGE ETH_MACMIIAR_CR_Div102 +#endif /* CLOCK_CORECLOCK < (20000000U) */ + +#define MIN(a, b) ((a < b) ? a : b) + +/* Internal flags for the DMA descriptors */ +#define DESC_OWN (0x80000000) +#define RX_DESC_FL (0x3FFF0000) +#define RX_DESC_FS (0x00000200) +#define RX_DESC_LS (0x00000100) +#define RX_DESC_RCH (0x00004000) +#define TX_DESC_TCH (0x00100000) +#define TX_DESC_IC (0x40000000) +#define TX_DESC_CIC (0x00C00000) +#define TX_DESC_LS (0x20000000) +#define TX_DESC_FS (0x10000000) + +struct eth_dma_desc { + uint32_t status; + uint32_t control; + char *buffer_addr; + struct eth_dma_desc *desc_next; + uint32_t reserved1_ext; + uint32_t reserved2; + uint32_t ts_low; + uint32_t ts_high; +} __attribute__((packed)); + +typedef struct eth_dma_desc edma_desc_t; + +/* Descriptors */ +static edma_desc_t rx_desc[ETH_RX_BUFFER_COUNT]; +static edma_desc_t tx_desc[ETH_TX_BUFFER_COUNT]; +static edma_desc_t *rx_curr; +static edma_desc_t *tx_curr; + +/* Buffers */ +static char rx_buffer[ETH_RX_BUFFER_COUNT][ETH_RX_BUFFER_SIZE]; +static char tx_buffer[ETH_TX_BUFFER_COUNT][ETH_TX_BUFFER_SIZE]; + +/* Mutex relying on interrupt */ +static mutex_t _tx = MUTEX_INIT; +static mutex_t _rx = MUTEX_INIT; +static mutex_t _dma_sync = MUTEX_INIT; + +/* Peripheral access exclusion mutex */ +static mutex_t send_lock = MUTEX_INIT; +static mutex_t receive_lock = MUTEX_INIT; + +static netdev_t *_netdev; + +/** Read or write a phy register, to write the register ETH_MACMIIAR_MW is to + * be passed as the higher nibble of the value */ +static unsigned _rw_phy(unsigned addr, unsigned reg, unsigned value) +{ + unsigned tmp; + + while (ETH->MACMIIAR & ETH_MACMIIAR_MB) ; + SDEBUG("rw_phy %x (%x): %x\n", addr, reg, value); + + tmp = (ETH->MACMIIAR & ETH_MACMIIAR_CR) | ETH_MACMIIAR_MB; + tmp |= (((addr & 0x1f) << 11) | ((reg & 0x1f) << 6)); + tmp |= (value >> 16); + + ETH->MACMIIDR = (value & 0xffff); + ETH->MACMIIAR = tmp; + while (ETH->MACMIIAR & ETH_MACMIIAR_MB) ; + + SDEBUG(" %lx\n", ETH->MACMIIDR); + return (ETH->MACMIIDR & 0x0000ffff); +} + +int32_t eth_phy_read(uint16_t addr, uint8_t reg) +{ + return _rw_phy(addr, reg, 0); +} + +int32_t eth_phy_write(uint16_t addr, uint8_t reg, uint16_t value) +{ + _rw_phy(addr, reg, (value & 0xffff) | (ETH_MACMIIAR_MW << 16)); + return 0; +} + +/** Set the mac address. The peripheral supports up to 4 MACs but only one is + * implemented */ +static void set_mac(const char *mac) +{ + ETH->MACA0HR &= 0xffff0000; + ETH->MACA0HR |= ((mac[0] << 8) | mac[1]); + ETH->MACA0LR = ((mac[2] << 24) | (mac[3] << 16) | (mac[4] << 8) | mac[5]); +} + +static void get_mac(char *out) +{ + unsigned t; + + t = ETH->MACA0HR; + out[0] = (t >> 8); + out[1] = (t & 0xff); + + t = ETH->MACA0LR; + out[2] = (t >> 24); + out[3] = (t >> 16); + out[4] = (t >> 8); + out[5] = (t & 0xff); +} + +/** Initialization of the DMA descriptors to be used */ +static void _init_dma(void) +{ + int i; + + for (i = 0; i < ETH_RX_BUFFER_COUNT; i++) { + rx_desc[i].status = DESC_OWN; + rx_desc[i].control = RX_DESC_RCH | (ETH_RX_BUFFER_SIZE & 0x0fff); + rx_desc[i].buffer_addr = &rx_buffer[i][0]; + rx_desc[i].desc_next = &rx_desc[i + 1]; + } + rx_desc[i - 1].desc_next = &rx_desc[0]; + + for (i = 0; i < ETH_TX_BUFFER_COUNT; i++) { + tx_desc[i].status = TX_DESC_TCH | TX_DESC_CIC; + tx_desc[i].buffer_addr = &tx_buffer[i][0]; + tx_desc[i].desc_next = &tx_desc[i + 1]; + } + tx_desc[i - 1].desc_next = &tx_desc[0]; + + rx_curr = &rx_desc[0]; + tx_curr = &tx_desc[0]; + + ETH->DMARDLAR = (uint32_t)rx_curr; + ETH->DMATDLAR = (uint32_t)tx_curr; + + /* initialize tx DMA */ + DMA_Stream_TypeDef *stream = dma_stream(eth_config.dma_stream); + + mutex_lock(&_dma_sync); + dma_poweron(eth_config.dma_stream); + dma_isr_enable(eth_config.dma_stream); + stream->CR = ((eth_config.dma_chan << 25) | + DMA_SxCR_MINC | DMA_SxCR_PINC | + DMA_SxCR_MBURST | DMA_SxCR_PBURST | + DMA_SxCR_PL_1 | DMA_SxCR_DIR_1 | DMA_SxCR_TCIE); + stream->FCR = DMA_SxFCR_DMDIS | DMA_SxFCR_FTH; +} + +int eth_init(void) +{ + /* enable APB2 clock */ + RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN; + + /* select RMII if necessary */ + if (eth_config.mode == RMII) { + SYSCFG->PMC |= SYSCFG_PMC_MII_RMII_SEL; + } + + /* initialize GPIO */ + for (int i = 0; i < (int) eth_config.mode; i++) { + gpio_init(eth_config.pins[i], GPIO_OUT); + gpio_init_af(eth_config.pins[i], GPIO_AF11); + } + + /* enable all clocks */ + RCC->AHB1ENR |= (RCC_AHB1ENR_ETHMACEN | RCC_AHB1ENR_ETHMACTXEN + | RCC_AHB1ENR_ETHMACRXEN | RCC_AHB1ENR_ETHMACPTPEN); + + /* reset the peripheral */ + RCC->AHB1RSTR |= RCC_AHB1RSTR_ETHMACRST; + RCC->AHB1RSTR &= ~RCC_AHB1RSTR_ETHMACRST; + + /* software reset */ + ETH->DMABMR |= ETH_DMABMR_SR; + while (ETH->DMABMR & ETH_DMABMR_SR) ; + + /* set the clock divider */ + while (ETH->MACMIIAR & ETH_MACMIIAR_MB) ; + ETH->MACMIIAR = CLOCK_RANGE; + + /* configure the PHY (standard for all PHY's) */ + /* if there's no PHY, this has no effect */ + eth_phy_write(eth_config.phy_addr, PHY_BMCR, BMCR_RESET); + + /* speed from conf */ + ETH->MACCR |= (ETH_MACCR_ROD | ETH_MACCR_IPCO | ETH_MACCR_APCS | + ((eth_config.speed & 0x0100) << 3) | + ((eth_config.speed & 0x2000) << 1)); + + /* pass all */ + //ETH->MACFFR |= ETH_MACFFR_RA; + /* perfect filter on address */ + ETH->MACFFR |= ETH_MACFFR_PAM | ETH_MACFFR_DAIF; + + /* store forward */ + ETH->DMAOMR |= ETH_DMAOMR_RSF | ETH_DMAOMR_TSF | ETH_DMAOMR_OSF; + + /* configure DMA */ + ETH->DMABMR = ETH_DMABMR_DA | ETH_DMABMR_AAB | ETH_DMABMR_FB | + ETH_DMABMR_RDP_32Beat | ETH_DMABMR_PBL_32Beat | ETH_DMABMR_EDE; + + set_mac(eth_config.mac); + + _init_dma(); + + NVIC_EnableIRQ(ETH_IRQn); + ETH->DMAIER |= ETH_DMAIER_NISE | ETH_DMAIER_TIE | ETH_DMAIER_RIE; + + /* enable */ + ETH->MACCR |= ETH_MACCR_TE; + ETH->DMAOMR |= ETH_DMAOMR_FTF; + ETH->MACCR |= ETH_MACCR_RE; + + ETH->DMAOMR |= ETH_DMAOMR_ST; + ETH->DMAOMR |= ETH_DMAOMR_SR; + + /* configure speed, do it at the end so the PHY had time to + * reset */ + eth_phy_write(eth_config.phy_addr, PHY_BMCR, eth_config.speed); + + return 0; +} + +static int eth_send(const char *data, unsigned len) +{ + DMA_Stream_TypeDef *stream = dma_stream(eth_config.dma_stream); + unsigned copy, count, sent = -1; + edma_desc_t *first = tx_curr; + edma_desc_t *last = tx_curr; + + count = len / ETH_TX_BUFFER_SIZE; + count += (len - (count * ETH_TX_BUFFER_SIZE) > 0) ? 1 : 0; + + /* safety check */ + if (count > ETH_TX_BUFFER_COUNT) { + return -1; + } + + while (count--) { + while (tx_curr->status & DESC_OWN) { + /* block until there's an available descriptor */ + SDEBUG("not avail\n"); + mutex_lock(&_tx); + } + + /* clear status field */ + tx_curr->status &= 0x0fffffff; + + /* copy buffer */ + copy = MIN(len, ETH_TX_BUFFER_SIZE); + stream->PAR = (uint32_t)data; + stream->M0AR = (uint32_t)tx_curr->buffer_addr; + stream->NDTR = (uint16_t)copy; + stream->CR |= DMA_SxCR_EN; + mutex_lock(&_dma_sync); + + tx_curr->control = (copy & 0x1fff); + len -= copy; + sent += copy; + + /* update pointers */ + last = tx_curr; + tx_curr = tx_curr->desc_next; + } + + /* set flags for first and last frames */ + first->status |= TX_DESC_FS; + last->status |= TX_DESC_LS | TX_DESC_IC; + + /* give the descriptors to the DMA */ + while (first != tx_curr) { + first->status |= DESC_OWN; + first = first->desc_next; + } + + /* start tx */ + ETH->DMATPDR = 0; + + return sent; +} + +static int _try_receive(char *data, int max_len, int block) +{ + int copy, len = 0; + int copied = 0; + int drop = (data || max_len > 0); + edma_desc_t *p = rx_curr; + + mutex_lock(&receive_lock); + for (int i = 0; i < ETH_RX_BUFFER_COUNT && len == 0; i++) { + /* try receiving, if the block is set, simply wait for the rest of + * the packet to complete, otherwise just break */ + while (p->status & DESC_OWN) { + if (block) { + mutex_lock(&_rx); + } + else { + break; + } + } + + /* amount of data to copy */ + copy = ETH_RX_BUFFER_SIZE; + if (p->status & (RX_DESC_LS | RX_DESC_FL)) { + len = ((p->status >> 16) & 0x3FFF) - 4; + copy = len - copied; + } + + if (drop) { + /* copy the data if possible */ + if (data && max_len >= copy) { + memcpy(data, p->buffer_addr, copy); + max_len -= copy; + } + else if (max_len < copy) { + len = -1; + } + p->status = DESC_OWN; + } + p = p->desc_next; + } + + if (drop) { + rx_curr = p; + } + + mutex_unlock(&receive_lock); + + return len; +} + +int eth_try_receive(char *data, unsigned max_len) +{ + return _try_receive(data, max_len, 0); +} + +int eth_receive_blocking(char *data, unsigned max_len) +{ + return _try_receive(data, max_len, 1); +} + +static void _isr(netdev_t *netdev) +{ + /* if the next descriptor is owned by the CPU we can get it */ + if (!(rx_curr->status & DESC_OWN)) { + netdev->event_callback(netdev, NETDEV_EVENT_RX_COMPLETE); + } +} + +void isr_eth(void) +{ + volatile unsigned tmp = ETH->DMASR; + + if ((tmp & ETH_DMASR_TS)) { + ETH->DMASR = ETH_DMASR_TS | ETH_DMASR_NIS; + mutex_unlock(&_tx); + } + + if ((tmp & ETH_DMASR_RS)) { + ETH->DMASR = ETH_DMASR_RS | ETH_DMASR_NIS; + mutex_unlock(&_rx); + if (_netdev) { + _netdev->event_callback(_netdev, NETDEV_EVENT_ISR); + } + } + + /* printf("r:%x\n\n", tmp); */ + + cortexm_isr_end(); +} + +void isr_eth_wkup(void) +{ + cortexm_isr_end(); +} + +void ETH_DMA_ISR(void) +{ + /* clear DMA done flag */ + int stream = eth_config.dma_stream; + dma_base(stream)->IFCR[dma_hl(stream)] = dma_ifc(stream); + mutex_unlock(&_dma_sync); + cortexm_isr_end(); +} + +static int _send(netdev_t *netdev, const struct iovec *vector, unsigned count) +{ + (void)netdev; + + int ret = 0, len = 0; + mutex_lock(&send_lock); + for (int i = 0; i < count && ret <= 0; i++) { + ret = eth_send(vector[i].iov_base, vector[i].iov_len); + len += ret; + } + SDEBUG("_send: %d %d\n", ret, len); + mutex_unlock(&send_lock); + +#ifdef MODULE_NETSTATS_L2 + netdev->stats.tx_bytes += len; +#endif + + if (ret < 0) { + return ret; + } + + return len; +} + +static int _recv(netdev_t *netdev, void *buf, size_t len, void *info) +{ + (void)info; + (void)netdev; + + int ret = _try_receive((char *)buf, len, 1); +#ifdef MODULE_NETSTATS_L2 + if (buf) { + netdev->stats.rx_count++; + netdev->stats.rx_bytes += len; + } +#endif + + SDEBUG("_recev: %d\n", ret); + + return ret; +} + +static int _get(netdev_t *dev, netopt_t opt, void *value, size_t max_len) +{ + int res = -1; + + switch (opt) { + case NETOPT_ADDRESS: + assert(max_len >= ETHERNET_ADDR_LEN); + get_mac((char *)value); + res = ETHERNET_ADDR_LEN; + break; + default: + res = netdev_eth_get(dev, opt, value, max_len); + break; + } + + return res; +} + +static int _set(netdev_t *dev, netopt_t opt, const void *value, size_t max_len) +{ + int res = -1; + + switch (opt) { + case NETOPT_ADDRESS: + assert(max_len >= ETHERNET_ADDR_LEN); + set_mac((char *)value); + res = ETHERNET_ADDR_LEN; + break; + default: + res = netdev_eth_set(dev, opt, value, max_len); + break; + } + + return res; +} + +static int _init(netdev_t *netdev) +{ + return eth_init(); +} + +const static netdev_driver_t netdev_driver_stm32f4eth = { + .send = _send, + .recv = _recv, + .init = _init, + .isr = _isr, + .get = _get, + .set = _set, +}; + +void eth_netdev_setup(netdev_t *netdev) +{ + _netdev = netdev; + netdev->driver = &netdev_driver_stm32f4eth; +} + +#endif diff --git a/drivers/include/net/phy.h b/drivers/include/net/phy.h new file mode 100644 index 000000000000..18aae066e925 --- /dev/null +++ b/drivers/include/net/phy.h @@ -0,0 +1,134 @@ +/* + * Copyright (C) 2016 TriaGnoSys GmbH + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for + * more details. + */ + +/** + * @defgroup ethernet_phy Ethernet PHY + * @brief Provides a Ethernet PHY abstraction + * @{ + * + * @file + * @brief Definitions for Ethernet PHY devices + * + * @author Víctor Ariño + */ + +#ifndef ETH_PHY_H +#define ETH_PHY_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +/* Ethernet PHY Common Registers */ +#define PHY_BMCR (0x00) +#define PHY_BSMR (0x01) +#define PHY_PHYIDR1 (0x02) +#define PHY_PHYIDR2 (0x03) +#define PHY_ANAR (0x04) +#define PHY_ANLPAR (0x05) +#define PHY_ANER (0x06) +#define PHY_ANNPTR (0x07) + +/* Ethernet PHY BMCR Fields */ +#define BMCR_RESET (0x8000) +#define BMCR_LOOPBACK (0x4000) +#define BMCR_SPEED_SELECT (0x2000) +#define BMCR_AN (0x1000) +#define BMCR_POWER_DOWN (0x0800) +#define BMCR_ISOLATE (0x0400) +#define BMCR_RESTART_AN (0x0200) +#define BMCR_DUPLEX_MODE (0x0100) +#define BMCR_COLLISION_TEST (0x0080) + +/* Ethernet PHY BSMR Fields */ +#define BSMR_100BASE_T4 (0x8000) +#define BSMR_100BASE_TX_FDUPLEX (0x4000) +#define BSMR_100BASE_TX_HDUPLEX (0x2000) +#define BSMR_10BASE_T_FDUPLEX (0x1000) +#define BSMR_10BASE_T_HDUPLEX (0x0800) +#define BSMR_NO_PREAMBLE (0x0040) +#define BSMR_AN_COMPLETE (0x0020) +#define BSMR_REMOTE_FAULT (0x0010) +#define BSMR_AN_ABILITY (0x0008) +#define BSMR_LINK_STATUS (0x0004) +#define BSMR_JABBER_DETECT (0x0002) +#define BSMR_EXTENDED_CAP (0x0001) + +/* Ethernet PHY PHYIDR1 Fields */ +#define PHYIDR1_OUI (0xffff) + +/* Ethernet PHY PHYIDR2 Fields */ +#define PHYIDR2_OUI (0xfe00) +#define PHYIDR2_MODEL (0x01f0) +#define PHYIDR2_REV (0x0007) + +/* Ethernet PHY ANAR Fields */ +#define ANAR_NEXT_PAGE (0x8000) +#define ANAR_REMOTE_FAULT (0x2000) +#define ANAR_PAUSE (0x0600) +#define ANAR_100BASE_T4 (0x0200) +#define ANAR_100BASE_TX_FDUPLEX (0x0100) +#define ANAR_100BASE_TX_HDUPLEX (0x0080) +#define ANAR_10BASE_T_FDUPLEX (0x0040) +#define ANAR_10BASE_T_HDUPLEX (0x0020) +#define ANAR_SELECTOR (0x000f) + +/* Ethernet PHY ANLPAR Fields */ +#define ANLPAR_NEXT_PAGE (0x8000) +#define ANLPAR_ACK (0x4000) +#define ANLPAR_REMOTE_FAULT (0x2000) +#define ANLPAR_PAUSE (0x0600) +#define ANLPAR_100BASE_T4 (0x0200) +#define ANLPAR_100BASE_TX_FDUPLEX (0x0100) +#define ANLPAR_100BASE_TX_HDUPLEX (0x0080) +#define ANLPAR_10BASE_T_FDUPLEX (0x0040) +#define ANLPAR_10BASE_T_HDUPLEX (0x0020) +#define ANLPAR_SELECTOR (0x000f) + +/* Ethernet PHY ANNPTR Fields */ +#define ANNPTR_NEXT_PAGE (0x8000) +#define ANNPTR_MSG_PAGE (0x2000) +#define ANNPTR_ACK2 (0x1000) +#define ANNPTR_TOGGLE_TX (0x0800) +#define ANNPTR_CODE (0x03ff) + +/* Ethernet PHY ANER Fields */ +#define ANER_PDF (0x0010) +#define ANER_LP_NEXT_PAGE_ABLE (0x0008) +#define ANER_NEXT_PAGE_ABLE (0x0004) +#define ANER_PAGE_RX (0x0002) +#define ANER_LP_AN_ABLE (0x0001) + +/** + * @brief Read a PHY register + * + * @param[in] addr address of the PHY to read + * @param[in] reg register to be read + * + * @return value in the register, or <=0 on error + */ +int32_t eth_phy_read(uint16_t addr, uint8_t reg); + +/** + * @brief Write a PHY register + * + * @param[in] addr address of the PHY to write + * @param[in] reg register to be written + * @param[in] value value to write into the register + * + * @return 0 in case of success or <=0 on error + */ +int32_t eth_phy_write(uint16_t addr, uint8_t reg, uint16_t value); + +#ifdef __cplusplus +} +#endif +/** @} */ +#endif /* ETH_PHY_H */ diff --git a/tests/stm32_eth_lwip/Makefile b/tests/stm32_eth_lwip/Makefile new file mode 100644 index 000000000000..e6da89c523f7 --- /dev/null +++ b/tests/stm32_eth_lwip/Makefile @@ -0,0 +1,17 @@ +APPLICATION = stm32_eth_lwip +include ../Makefile.tests_common + +BOARD := stm32f4discovery + +FEATURES_REQUIRED += periph_stm32_eth + +USEMODULE += lwip +USEMODULE += lwip_netdev +USEMODULE += lwip_udp +USEMODULE += lwip_sock_udp +USEMODULE += lwip_ethernet +USEMODULE += lwip_ipv4 +USEMODULE += lwip_arp +USEMODULE += netdev_eth + +include $(RIOTBASE)/Makefile.include diff --git a/tests/stm32_eth_lwip/README.md b/tests/stm32_eth_lwip/README.md new file mode 100644 index 000000000000..97eda3b77e07 --- /dev/null +++ b/tests/stm32_eth_lwip/README.md @@ -0,0 +1,21 @@ +Tests for stm32 Ethernet periph driver +====================================== + +This tests the stm32 Ethernet driver using lwIP and IPv4. It implements a very +simple UDP echo server at the configured address (by default 172.16.19.5) and +port `12345`. + +To interface with the board configure the local IP address of the available +interface (e.g. eth1) with the gateway address (by default 172.16.19.1) +and execute a tool such as netcat to send UPD messages to the stm32. + +```sh +# Configure IP on the available interface +ifconfig eth1 172.16.19.1/24 + +# Start netcat +nc -u 172.16.19.5 12345 +``` + +The board will reply all the messages sent to it (with a maximum length of 128 +bytes). diff --git a/tests/stm32_eth_lwip/main.c b/tests/stm32_eth_lwip/main.c new file mode 100644 index 000000000000..390273c12e3e --- /dev/null +++ b/tests/stm32_eth_lwip/main.c @@ -0,0 +1,85 @@ +/* + * Copyright (C) 2017 TriaGnoSys GmbH + * + * This file is subject to the terms and conditions of the GNU Lesser + * General Public License v2.1. See the file LICENSE in the top level + * directory for more details. + */ + +/** + * @{ + * + * @file + * @brief Show case application for stm32 eth driver + * + * @author Víctor Ariño + * + * @} + */ + +#include + +#include "net/netdev.h" +#include "net/netdev/eth.h" +#include "net/sock/udp.h" +#include "net/sock/udp.h" +#include "net/phy.h" + +#include "lwip.h" +#include "lwip/netif.h" +#include "lwip/netif/netdev.h" + +#include "xtimer.h" + +#define SET_IP(x, ...) IP4_ADDR(x, __VA_ARGS__) + +static netdev_t stm32f4eth; +static struct netif netif; +static ip4_addr_t local_ip, netmask, gw; +static sock_udp_ep_t local = SOCK_IPV4_EP_ANY; +static sock_udp_ep_t remote; +static uint8_t buff[128]; + +void eth_netdev_setup(netdev_t *netdev); + +int main(void) +{ + puts("Booting"); + + eth_netdev_setup(&stm32f4eth); + + SET_IP(&local_ip, 172, 16, 19, 5); + SET_IP(&netmask, 255, 255, 255, 0); + SET_IP(&gw, 172, 16, 19, 1); + + if (netif_add(&netif, &local_ip, &netmask, &gw, &stm32f4eth, + lwip_netdev_init, tcpip_input) == NULL) { + puts("error netif_add"); + return -1; + } + else if (netif.state != NULL) { + netif_set_default(&netif); + } + + sock_udp_t sock; + local.port = 12345; + + if (sock_udp_create(&sock, &local, NULL, 0) < 0) { + puts("Error creating UDP sock"); + return 1; + } + + puts("Waiting for messages..."); + while (1) { + ssize_t res; + if ((res = sock_udp_recv(&sock, buff, sizeof(buff), SOCK_NO_TIMEOUT, + &remote)) >= 0) { + puts("Received a message"); + if (sock_udp_send(&sock, buff, res, &remote) < 0) { + puts("Error sending reply"); + } + } + } + + return 0; +} From 4729bea46e44b2bf65b96970c5d6aa97dfd6a95b Mon Sep 17 00:00:00 2001 From: Robin Date: Sat, 15 Dec 2018 02:23:37 +0100 Subject: [PATCH 2/3] stm32_eth: Multiple Improvements of the original codebase stm32eth: Move to stm32_common periph cpu/stm32_periph_eth: Rebase to current master branch - Update DMA to use new vendor headers - Update send to use iolist. It looks like the packet headers are now transfered as seperate iolist entries which results in the eth periph sending each header as own packet. To fix this a rather ugly workaround is used where the whole iolist content is first copied to a static buffer. This will be fixed soon in another commit - If MAC is set to zero use luid to generate one - Small code style fixes cpu/stm312f7: Add periph config for on-board ethernet boards/nucleo-f767zi: Add config for on board ethernet tests/stm32_eth_lwip: Remove board restriction boards/common/nucleo: Add luid module if stm32 ethernet is used tests/stm32_eth_gnrc: Add Testcase for gnrc using the stm32 eth periph stm32_eth: Rework netdev driver layour tests/stm32_eth_*: Use netdev driver header file for prototypes stm32_eth: Add auto init for stm32 eth netdev driver boards/stm32: Enable ethernet conf for nucleo boards stm32_eth_auto_init: Add dont be pendantic flag stm32_eth: Remove dma specific stuff from periph_cpu.h Looks like this was implemented in PR #9171 and 021697ae94 with the same interface. stm32_eth: Remove eth feature from stm32f4discovery boards stm32_eth: Migrate to stm32 DMA API stm32_eth: Add iolist to module deps stm32_eth: Rework send function to use iolist stm32_eth: Fix ci build warnings stm32_eth: Fix bug introduced with iolist usage stm32_eth: Remove redundant static buffer stm32_eth: Fix feature dependencies stm32_eth: Fix wrong header guard name stm32_eth: Implement correct l2 netstats interface stm32_eth: Rename public functions to stm32_eth_* stm32_eth: Fix doccheck stm32_eth: Move register DEFINE to appropriate header file stm32_eth: remove untested configuration for f446ze boards stm32_eth: Move periph configuration struct to stm32_common stm32_eth: Fix naming of eth_phy_read and eth_phy_write stm32_eth: Remove obsolete test applications --- boards/nucleo-f767zi/Makefile.dep | 4 + boards/nucleo-f767zi/Makefile.features | 2 + boards/nucleo-f767zi/include/periph_conf.h | 37 +++ boards/stm32f4discovery/Makefile.features | 2 - boards/stm32f4discovery/include/periph_conf.h | 35 -- cpu/stm32_common/include/periph_cpu_common.h | 162 +++++++++ cpu/{stm32f4 => stm32_common}/periph/eth.c | 314 ++++-------------- cpu/stm32f4/include/periph_cpu.h | 116 ------- drivers/Makefile.dep | 8 + drivers/include/net/phy.h | 134 -------- drivers/include/stm32_eth.h | 31 ++ drivers/stm32_eth/Makefile | 1 + drivers/stm32_eth/doc.txt | 13 + drivers/stm32_eth/stm32_eth.c | 157 +++++++++ sys/auto_init/auto_init.c | 5 + sys/auto_init/netif/auto_init_stm32_eth.c | 30 ++ tests/stm32_eth_lwip/Makefile | 17 - tests/stm32_eth_lwip/README.md | 21 -- tests/stm32_eth_lwip/main.c | 85 ----- 19 files changed, 517 insertions(+), 657 deletions(-) rename cpu/{stm32f4 => stm32_common}/periph/eth.c (55%) delete mode 100644 drivers/include/net/phy.h create mode 100644 drivers/include/stm32_eth.h create mode 100644 drivers/stm32_eth/Makefile create mode 100644 drivers/stm32_eth/doc.txt create mode 100644 drivers/stm32_eth/stm32_eth.c create mode 100644 sys/auto_init/netif/auto_init_stm32_eth.c delete mode 100644 tests/stm32_eth_lwip/Makefile delete mode 100644 tests/stm32_eth_lwip/README.md delete mode 100644 tests/stm32_eth_lwip/main.c diff --git a/boards/nucleo-f767zi/Makefile.dep b/boards/nucleo-f767zi/Makefile.dep index 729485827299..b610f47b8e40 100644 --- a/boards/nucleo-f767zi/Makefile.dep +++ b/boards/nucleo-f767zi/Makefile.dep @@ -1 +1,5 @@ +ifneq (,$(filter netdev_default gnrc_netdev_default,$(USEMODULE))) + USEMODULE += stm32_eth +endif + include $(RIOTBOARD)/common/nucleo/Makefile.dep diff --git a/boards/nucleo-f767zi/Makefile.features b/boards/nucleo-f767zi/Makefile.features index c4dbc5e064c1..abd111b99428 100644 --- a/boards/nucleo-f767zi/Makefile.features +++ b/boards/nucleo-f767zi/Makefile.features @@ -6,6 +6,8 @@ FEATURES_PROVIDED += periph_rtt FEATURES_PROVIDED += periph_spi FEATURES_PROVIDED += periph_timer FEATURES_PROVIDED += periph_uart +FEATURES_PROVIDED += periph_eth +FEATURES_PROVIDED += periph_stm32_eth # load the common Makefile.features for Nucleo boards include $(RIOTBOARD)/common/nucleo144/Makefile.features diff --git a/boards/nucleo-f767zi/include/periph_conf.h b/boards/nucleo-f767zi/include/periph_conf.h index 15ae0f3b8e78..e80f8c31d390 100644 --- a/boards/nucleo-f767zi/include/periph_conf.h +++ b/boards/nucleo-f767zi/include/periph_conf.h @@ -40,11 +40,13 @@ static const dma_conf_t dma_config[] = { { .stream = 4 }, /* DMA1 Stream 4 - USART3_TX */ { .stream = 14 }, /* DMA2 Stream 6 - USART6_TX */ { .stream = 6 }, /* DMA1 Stream 6 - USART2_TX */ + { .stream = 8 }, /* DMA2 Stream 8 - ETH_TX */ }; #define DMA_0_ISR isr_dma1_stream4 #define DMA_1_ISR isr_dma2_stream6 #define DMA_2_ISR isr_dma1_stream6 +#define DMA_3_ISR isr_dma2_stream0 #define DMA_NUMOF (sizeof(dma_config) / sizeof(dma_config[0])) #endif @@ -158,6 +160,41 @@ static const spi_conf_t spi_config[] = { #define SPI_NUMOF (sizeof(spi_config) / sizeof(spi_config[0])) /** @} */ + +/** + * @name ETH configuration + * @{ + */ +#define ETH_NUMOF (1) +#define ETH_RX_BUFFER_COUNT (4) +#define ETH_TX_BUFFER_COUNT (4) + +#define ETH_RX_BUFFER_SIZE (1524) +#define ETH_TX_BUFFER_SIZE (1524) + +#define ETH_DMA_ISR isr_dma2_stream0 + +static const eth_conf_t eth_config = { + .mode = RMII, + .mac = { 0 }, + .speed = ETH_SPEED_100TX_FD, + .dma_chan = 0, + .dma_stream = 8, + .phy_addr = 0x01, + .pins = { + GPIO_PIN(PORT_G, 13), + GPIO_PIN(PORT_B, 13), + GPIO_PIN(PORT_G, 11), + GPIO_PIN(PORT_C, 4), + GPIO_PIN(PORT_C, 5), + GPIO_PIN(PORT_A, 7), + GPIO_PIN(PORT_C, 1), + GPIO_PIN(PORT_A, 2), + GPIO_PIN(PORT_A, 1), + } +}; +/** @} */ + #ifdef __cplusplus } #endif diff --git a/boards/stm32f4discovery/Makefile.features b/boards/stm32f4discovery/Makefile.features index 5bff2bb9f418..fcdb12986960 100644 --- a/boards/stm32f4discovery/Makefile.features +++ b/boards/stm32f4discovery/Makefile.features @@ -1,12 +1,10 @@ # Put defined MCU peripherals here (in alphabetical order) FEATURES_PROVIDED += periph_adc FEATURES_PROVIDED += periph_dac -FEATURES_PROVIDED += periph_eth FEATURES_PROVIDED += periph_i2c FEATURES_PROVIDED += periph_pwm FEATURES_PROVIDED += periph_rtc FEATURES_PROVIDED += periph_spi -FEATURES_PROVIDED += periph_stm32_eth FEATURES_PROVIDED += periph_timer FEATURES_PROVIDED += periph_uart diff --git a/boards/stm32f4discovery/include/periph_conf.h b/boards/stm32f4discovery/include/periph_conf.h index ad0a8600ca23..e209748d014d 100644 --- a/boards/stm32f4discovery/include/periph_conf.h +++ b/boards/stm32f4discovery/include/periph_conf.h @@ -211,41 +211,6 @@ static const i2c_conf_t i2c_config[] = { #define I2C_NUMOF (sizeof(i2c_config) / sizeof(i2c_config[0])) /** @} */ -/** - * @name ETH configuration - * @{ - */ -#define ETH_NUMOF (1) -#define ETH_RX_BUFFER_COUNT (4) -#define ETH_TX_BUFFER_COUNT (4) - -#define ETH_RX_BUFFER_SIZE (1524) -#define ETH_TX_BUFFER_SIZE (1524) - -#define ETH_DMA_ISR isr_dma2_stream0 - -static const eth_conf_t eth_config = { - .mode = RMII, - .mac = { 1, 2, 3, 4, 5, 6 }, - .speed = ETH_SPEED_100TX_FD, - .dma_chan = 0, - .dma_stream = 8, - .phy_addr = 0x01, - .pins = { - GPIO_PIN(PORT_B, 12), - GPIO_PIN(PORT_B, 13), - GPIO_PIN(PORT_B, 11), - GPIO_PIN(PORT_C, 4), - GPIO_PIN(PORT_C, 5), - GPIO_PIN(PORT_A, 7), - GPIO_PIN(PORT_C, 1), - GPIO_PIN(PORT_A, 2), - GPIO_PIN(PORT_A, 1), - } -}; - -/** @} */ - #ifdef __cplusplus } #endif diff --git a/cpu/stm32_common/include/periph_cpu_common.h b/cpu/stm32_common/include/periph_cpu_common.h index 19e1bc060ac3..f8f58836b180 100644 --- a/cpu/stm32_common/include/periph_cpu_common.h +++ b/cpu/stm32_common/include/periph_cpu_common.h @@ -708,6 +708,168 @@ int dma_configure(dma_t dma, int chan, const volatile void *src, volatile void * #include "candev_stm32.h" #endif +#ifdef MODULE_STM32_ETH + +/** + * @brief Ethernet Peripheral configuration + */ +typedef struct { + enum { + MII = 18, /**< Configuration for MII */ + RMII = 9, /**< Configuration for RMII */ + SMI = 2, /**< Configuration for SMI */ + } mode; /**< Select configuration mode */ + enum { + ETH_SPEED_10T_HD = 0x0000, + ETH_SPEED_10T_FD = 0x0100, + ETH_SPEED_100TX_HD = 0x2000, + ETH_SPEED_100TX_FD = 0x2100, + } speed; /**< Speed selection */ + uint8_t dma; /**< Locical CMA Descriptor used for TX */ + uint8_t dma_chan; /**< DMA channel used for TX */ + char mac[6]; /**< Et hernet MAC address */ + char phy_addr; /**< PHY address */ + gpio_t pins[]; /**< Pins to use. MII requires 18 pins, + RMII 9 and SMI 9. Not all speeds are + supported by all modes. */ +} eth_conf_t; + +/** +* @name Ethernet PHY Common Registers +* @{ +*/ +#define PHY_BMCR (0x00) +#define PHY_BSMR (0x01) +#define PHY_PHYIDR1 (0x02) +#define PHY_PHYIDR2 (0x03) +#define PHY_ANAR (0x04) +#define PHY_ANLPAR (0x05) +#define PHY_ANER (0x06) +#define PHY_ANNPTR (0x07) +/** @} */ + +/** +* @name Ethernet PHY BMCR Fields +* @{ +*/ +#define BMCR_RESET (0x8000) +#define BMCR_LOOPBACK (0x4000) +#define BMCR_SPEED_SELECT (0x2000) +#define BMCR_AN (0x1000) +#define BMCR_POWER_DOWN (0x0800) +#define BMCR_ISOLATE (0x0400) +#define BMCR_RESTART_AN (0x0200) +#define BMCR_DUPLEX_MODE (0x0100) +#define BMCR_COLLISION_TEST (0x0080) +/** @} */ + +/** +* @name Ethernet PHY BSMR Fields +* @{ +*/ +#define BSMR_100BASE_T4 (0x8000) +#define BSMR_100BASE_TX_FDUPLEX (0x4000) +#define BSMR_100BASE_TX_HDUPLEX (0x2000) +#define BSMR_10BASE_T_FDUPLEX (0x1000) +#define BSMR_10BASE_T_HDUPLEX (0x0800) +#define BSMR_NO_PREAMBLE (0x0040) +#define BSMR_AN_COMPLETE (0x0020) +#define BSMR_REMOTE_FAULT (0x0010) +#define BSMR_AN_ABILITY (0x0008) +#define BSMR_LINK_STATUS (0x0004) +#define BSMR_JABBER_DETECT (0x0002) +#define BSMR_EXTENDED_CAP (0x0001) +/** @} */ + +/** +* @name Ethernet PHY PHYIDR1 Fields +*/ +#define PHYIDR1_OUI (0xffff) + +/** +* @name Ethernet PHY PHYIDR2 Fields +* @{ +*/ +#define PHYIDR2_OUI (0xfe00) +#define PHYIDR2_MODEL (0x01f0) +#define PHYIDR2_REV (0x0007) +/** @} */ + +/** +* @name Ethernet PHY ANAR Fields +* @{ +*/ +#define ANAR_NEXT_PAGE (0x8000) +#define ANAR_REMOTE_FAULT (0x2000) +#define ANAR_PAUSE (0x0600) +#define ANAR_100BASE_T4 (0x0200) +#define ANAR_100BASE_TX_FDUPLEX (0x0100) +#define ANAR_100BASE_TX_HDUPLEX (0x0080) +#define ANAR_10BASE_T_FDUPLEX (0x0040) +#define ANAR_10BASE_T_HDUPLEX (0x0020) +#define ANAR_SELECTOR (0x000f) +/** @} */ + +/** +* @name Ethernet PHY ANLPAR Fields +* @{ +*/ +#define ANLPAR_NEXT_PAGE (0x8000) +#define ANLPAR_ACK (0x4000) +#define ANLPAR_REMOTE_FAULT (0x2000) +#define ANLPAR_PAUSE (0x0600) +#define ANLPAR_100BASE_T4 (0x0200) +#define ANLPAR_100BASE_TX_FDUPLEX (0x0100) +#define ANLPAR_100BASE_TX_HDUPLEX (0x0080) +#define ANLPAR_10BASE_T_FDUPLEX (0x0040) +#define ANLPAR_10BASE_T_HDUPLEX (0x0020) +#define ANLPAR_SELECTOR (0x000f) +/** @} */ + +/** +* @name Ethernet PHY ANNPTR Fields +* @{ +*/ +#define ANNPTR_NEXT_PAGE (0x8000) +#define ANNPTR_MSG_PAGE (0x2000) +#define ANNPTR_ACK2 (0x1000) +#define ANNPTR_TOGGLE_TX (0x0800) +#define ANNPTR_CODE (0x03ff) +/** @} */ + +/** +* @name Ethernet PHY ANER Fields +* @{ +*/ +#define ANER_PDF (0x0010) +#define ANER_LP_NEXT_PAGE_ABLE (0x0008) +#define ANER_NEXT_PAGE_ABLE (0x0004) +#define ANER_PAGE_RX (0x0002) +#define ANER_LP_AN_ABLE (0x0001) +/** @} */ + +/** + * @brief Read a PHY register + * + * @param[in] addr address of the PHY to read + * @param[in] reg register to be read + * + * @return value in the register, or <=0 on error + */ +int32_t stm32_eth_phy_read(uint16_t addr, uint8_t reg); + +/** + * @brief Write a PHY register + * + * @param[in] addr address of the PHY to write + * @param[in] reg register to be written + * @param[in] value value to write into the register + * + * @return 0 in case of success or <=0 on error + */ +int32_t stm32_eth_phy_write(uint16_t addr, uint8_t reg, uint16_t value); +#endif /* MODULE_STM32_ETH */ + #ifdef __cplusplus } #endif diff --git a/cpu/stm32f4/periph/eth.c b/cpu/stm32_common/periph/eth.c similarity index 55% rename from cpu/stm32f4/periph/eth.c rename to cpu/stm32_common/periph/eth.c index f336172f8ee9..1225c78c8abf 100644 --- a/cpu/stm32f4/periph/eth.c +++ b/cpu/stm32_common/periph/eth.c @@ -17,31 +17,16 @@ * * @} */ - -#include "cpu.h" #include "mutex.h" -#include "assert.h" -#include "periph_conf.h" #include "periph/gpio.h" - -#include "board.h" - -#include "net/netdev.h" -#include "net/netdev/eth.h" -#include "net/eui64.h" +#include "luid.h" #include "net/ethernet.h" -#include "net/netstats.h" -#include "net/phy.h" - +#include "iolist.h" #define ENABLE_DEBUG (0) #include "debug.h" -#define SDEBUG(...) DEBUG("eth: " __VA_ARGS__) - #include - #if ETH_NUMOF - /* Set the value of the divider with the clock configured */ #if !defined(CLOCK_CORECLOCK) || CLOCK_CORECLOCK < (20000000U) #error This peripheral requires a CORECLOCK of at least 20MHz @@ -57,8 +42,6 @@ #define CLOCK_RANGE ETH_MACMIIAR_CR_Div102 #endif /* CLOCK_CORECLOCK < (20000000U) */ -#define MIN(a, b) ((a < b) ? a : b) - /* Internal flags for the DMA descriptors */ #define DESC_OWN (0x80000000) #define RX_DESC_FL (0x3FFF0000) @@ -94,17 +77,6 @@ static edma_desc_t *tx_curr; static char rx_buffer[ETH_RX_BUFFER_COUNT][ETH_RX_BUFFER_SIZE]; static char tx_buffer[ETH_TX_BUFFER_COUNT][ETH_TX_BUFFER_SIZE]; -/* Mutex relying on interrupt */ -static mutex_t _tx = MUTEX_INIT; -static mutex_t _rx = MUTEX_INIT; -static mutex_t _dma_sync = MUTEX_INIT; - -/* Peripheral access exclusion mutex */ -static mutex_t send_lock = MUTEX_INIT; -static mutex_t receive_lock = MUTEX_INIT; - -static netdev_t *_netdev; - /** Read or write a phy register, to write the register ETH_MACMIIAR_MW is to * be passed as the higher nibble of the value */ static unsigned _rw_phy(unsigned addr, unsigned reg, unsigned value) @@ -112,7 +84,7 @@ static unsigned _rw_phy(unsigned addr, unsigned reg, unsigned value) unsigned tmp; while (ETH->MACMIIAR & ETH_MACMIIAR_MB) ; - SDEBUG("rw_phy %x (%x): %x\n", addr, reg, value); + DEBUG("stm32_eth: rw_phy %x (%x): %x\n", addr, reg, value); tmp = (ETH->MACMIIAR & ETH_MACMIIAR_CR) | ETH_MACMIIAR_MB; tmp |= (((addr & 0x1f) << 11) | ((reg & 0x1f) << 6)); @@ -122,31 +94,22 @@ static unsigned _rw_phy(unsigned addr, unsigned reg, unsigned value) ETH->MACMIIAR = tmp; while (ETH->MACMIIAR & ETH_MACMIIAR_MB) ; - SDEBUG(" %lx\n", ETH->MACMIIDR); + DEBUG("stm32_eth: %lx\n", ETH->MACMIIDR); return (ETH->MACMIIDR & 0x0000ffff); } -int32_t eth_phy_read(uint16_t addr, uint8_t reg) +int32_t stm32_eth_phy_read(uint16_t addr, uint8_t reg) { return _rw_phy(addr, reg, 0); } -int32_t eth_phy_write(uint16_t addr, uint8_t reg, uint16_t value) +int32_t stm32_eth_phy_write(uint16_t addr, uint8_t reg, uint16_t value) { _rw_phy(addr, reg, (value & 0xffff) | (ETH_MACMIIAR_MW << 16)); return 0; } -/** Set the mac address. The peripheral supports up to 4 MACs but only one is - * implemented */ -static void set_mac(const char *mac) -{ - ETH->MACA0HR &= 0xffff0000; - ETH->MACA0HR |= ((mac[0] << 8) | mac[1]); - ETH->MACA0LR = ((mac[2] << 24) | (mac[3] << 16) | (mac[4] << 8) | mac[5]); -} - -static void get_mac(char *out) +void stm32_eth_get_mac(char *out) { unsigned t; @@ -161,23 +124,35 @@ static void get_mac(char *out) out[5] = (t & 0xff); } +/** Set the mac address. The peripheral supports up to 4 MACs but only one is + * implemented */ +void stm32_eth_set_mac(const char *mac) +{ + ETH->MACA0HR &= 0xffff0000; + ETH->MACA0HR |= ((mac[0] << 8) | mac[1]); + ETH->MACA0LR = ((mac[2] << 24) | (mac[3] << 16) | (mac[4] << 8) | mac[5]); +} + /** Initialization of the DMA descriptors to be used */ -static void _init_dma(void) +static void _init_buffer(void) { int i; - for (i = 0; i < ETH_RX_BUFFER_COUNT; i++) { rx_desc[i].status = DESC_OWN; rx_desc[i].control = RX_DESC_RCH | (ETH_RX_BUFFER_SIZE & 0x0fff); rx_desc[i].buffer_addr = &rx_buffer[i][0]; - rx_desc[i].desc_next = &rx_desc[i + 1]; + if((i+1) < ETH_RX_BUFFER_COUNT) { + rx_desc[i].desc_next = &rx_desc[i + 1]; + } } rx_desc[i - 1].desc_next = &rx_desc[0]; for (i = 0; i < ETH_TX_BUFFER_COUNT; i++) { tx_desc[i].status = TX_DESC_TCH | TX_DESC_CIC; tx_desc[i].buffer_addr = &tx_buffer[i][0]; - tx_desc[i].desc_next = &tx_desc[i + 1]; + if((i+1) < ETH_RX_BUFFER_COUNT) { + tx_desc[i].desc_next = &tx_desc[i + 1]; + } } tx_desc[i - 1].desc_next = &tx_desc[0]; @@ -186,22 +161,11 @@ static void _init_dma(void) ETH->DMARDLAR = (uint32_t)rx_curr; ETH->DMATDLAR = (uint32_t)tx_curr; - - /* initialize tx DMA */ - DMA_Stream_TypeDef *stream = dma_stream(eth_config.dma_stream); - - mutex_lock(&_dma_sync); - dma_poweron(eth_config.dma_stream); - dma_isr_enable(eth_config.dma_stream); - stream->CR = ((eth_config.dma_chan << 25) | - DMA_SxCR_MINC | DMA_SxCR_PINC | - DMA_SxCR_MBURST | DMA_SxCR_PBURST | - DMA_SxCR_PL_1 | DMA_SxCR_DIR_1 | DMA_SxCR_TCIE); - stream->FCR = DMA_SxFCR_DMDIS | DMA_SxFCR_FTH; } -int eth_init(void) +int stm32_eth_init(void) { + char hwaddr[ETHERNET_ADDR_LEN]; /* enable APB2 clock */ RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN; @@ -234,7 +198,7 @@ int eth_init(void) /* configure the PHY (standard for all PHY's) */ /* if there's no PHY, this has no effect */ - eth_phy_write(eth_config.phy_addr, PHY_BMCR, BMCR_RESET); + stm32_eth_phy_write(eth_config.phy_addr, PHY_BMCR, BMCR_RESET); /* speed from conf */ ETH->MACCR |= (ETH_MACCR_ROD | ETH_MACCR_IPCO | ETH_MACCR_APCS | @@ -253,9 +217,14 @@ int eth_init(void) ETH->DMABMR = ETH_DMABMR_DA | ETH_DMABMR_AAB | ETH_DMABMR_FB | ETH_DMABMR_RDP_32Beat | ETH_DMABMR_PBL_32Beat | ETH_DMABMR_EDE; - set_mac(eth_config.mac); + if(eth_config.mac[0] != 0) { + stm32_eth_set_mac(eth_config.mac); + } else { + luid_get(hwaddr, ETHERNET_ADDR_LEN); + stm32_eth_set_mac(hwaddr); + } - _init_dma(); + _init_buffer(); NVIC_EnableIRQ(ETH_IRQn); ETH->DMAIER |= ETH_DMAIER_NISE | ETH_DMAIER_TIE | ETH_DMAIER_RIE; @@ -268,69 +237,57 @@ int eth_init(void) ETH->DMAOMR |= ETH_DMAOMR_ST; ETH->DMAOMR |= ETH_DMAOMR_SR; - /* configure speed, do it at the end so the PHY had time to + /* configure speed, do it at the end so the PHY had time to * reset */ - eth_phy_write(eth_config.phy_addr, PHY_BMCR, eth_config.speed); + stm32_eth_phy_write(eth_config.phy_addr, PHY_BMCR, eth_config.speed); return 0; } -static int eth_send(const char *data, unsigned len) +int stm32_eth_send(const struct iolist *iolist) { - DMA_Stream_TypeDef *stream = dma_stream(eth_config.dma_stream); - unsigned copy, count, sent = -1; - edma_desc_t *first = tx_curr; - edma_desc_t *last = tx_curr; - - count = len / ETH_TX_BUFFER_SIZE; - count += (len - (count * ETH_TX_BUFFER_SIZE) > 0) ? 1 : 0; + unsigned len = iolist_size(iolist); + int ret = 0; /* safety check */ - if (count > ETH_TX_BUFFER_COUNT) { + if (len > ETH_TX_BUFFER_SIZE) { + DEBUG("stm32_eth: Error iolist_size > ETH_TX_BUFFER_SIZE\n"); return -1; } - while (count--) { - while (tx_curr->status & DESC_OWN) { - /* block until there's an available descriptor */ - SDEBUG("not avail\n"); - mutex_lock(&_tx); - } - - /* clear status field */ - tx_curr->status &= 0x0fffffff; + /* block until there's an available descriptor */ + while (tx_curr->status & DESC_OWN) { + DEBUG("stm32_eth: not avail\n"); + } - /* copy buffer */ - copy = MIN(len, ETH_TX_BUFFER_SIZE); - stream->PAR = (uint32_t)data; - stream->M0AR = (uint32_t)tx_curr->buffer_addr; - stream->NDTR = (uint16_t)copy; - stream->CR |= DMA_SxCR_EN; - mutex_lock(&_dma_sync); + /* clear status field */ + tx_curr->status &= 0x0fffffff; - tx_curr->control = (copy & 0x1fff); - len -= copy; - sent += copy; + dma_acquire(eth_config.dma); + for (; iolist; iolist = iolist->iol_next) + { + ret += dma_transfer(eth_config.dma, eth_config.dma_chan, iolist->iol_base, + tx_curr->buffer_addr+ret, iolist->iol_len, DMA_MEM_TO_MEM, DMA_INC_BOTH_ADDR); + } - /* update pointers */ - last = tx_curr; - tx_curr = tx_curr->desc_next; + dma_release(eth_config.dma); + if (ret < 0) { + DEBUG("stm32_eth: Failure in dma_transfer\n"); + return ret; } + tx_curr->control = (len & 0x1fff); /* set flags for first and last frames */ - first->status |= TX_DESC_FS; - last->status |= TX_DESC_LS | TX_DESC_IC; + tx_curr->status |= TX_DESC_FS; + tx_curr->status |= TX_DESC_LS | TX_DESC_IC; /* give the descriptors to the DMA */ - while (first != tx_curr) { - first->status |= DESC_OWN; - first = first->desc_next; - } + tx_curr->status |= DESC_OWN; + tx_curr = tx_curr->desc_next; /* start tx */ ETH->DMATPDR = 0; - - return sent; + return ret; } static int _try_receive(char *data, int max_len, int block) @@ -339,14 +296,11 @@ static int _try_receive(char *data, int max_len, int block) int copied = 0; int drop = (data || max_len > 0); edma_desc_t *p = rx_curr; - - mutex_lock(&receive_lock); for (int i = 0; i < ETH_RX_BUFFER_COUNT && len == 0; i++) { /* try receiving, if the block is set, simply wait for the rest of * the packet to complete, otherwise just break */ while (p->status & DESC_OWN) { if (block) { - mutex_lock(&_rx); } else { break; @@ -378,161 +332,27 @@ static int _try_receive(char *data, int max_len, int block) rx_curr = p; } - mutex_unlock(&receive_lock); - return len; } -int eth_try_receive(char *data, unsigned max_len) +int stm32_eth_try_receive(char *data, unsigned max_len) { return _try_receive(data, max_len, 0); } -int eth_receive_blocking(char *data, unsigned max_len) +int stm32_eth_receive_blocking(char *data, unsigned max_len) { return _try_receive(data, max_len, 1); } -static void _isr(netdev_t *netdev) -{ - /* if the next descriptor is owned by the CPU we can get it */ - if (!(rx_curr->status & DESC_OWN)) { - netdev->event_callback(netdev, NETDEV_EVENT_RX_COMPLETE); - } -} - -void isr_eth(void) -{ - volatile unsigned tmp = ETH->DMASR; - - if ((tmp & ETH_DMASR_TS)) { - ETH->DMASR = ETH_DMASR_TS | ETH_DMASR_NIS; - mutex_unlock(&_tx); - } - - if ((tmp & ETH_DMASR_RS)) { - ETH->DMASR = ETH_DMASR_RS | ETH_DMASR_NIS; - mutex_unlock(&_rx); - if (_netdev) { - _netdev->event_callback(_netdev, NETDEV_EVENT_ISR); - } - } - - /* printf("r:%x\n\n", tmp); */ - - cortexm_isr_end(); -} - -void isr_eth_wkup(void) +int stm32_eth_get_rx_status_owned(void) { - cortexm_isr_end(); + return (!(rx_curr->status & DESC_OWN)); } -void ETH_DMA_ISR(void) +void stm32_eth_isr_eth_wkup(void) { - /* clear DMA done flag */ - int stream = eth_config.dma_stream; - dma_base(stream)->IFCR[dma_hl(stream)] = dma_ifc(stream); - mutex_unlock(&_dma_sync); cortexm_isr_end(); } -static int _send(netdev_t *netdev, const struct iovec *vector, unsigned count) -{ - (void)netdev; - - int ret = 0, len = 0; - mutex_lock(&send_lock); - for (int i = 0; i < count && ret <= 0; i++) { - ret = eth_send(vector[i].iov_base, vector[i].iov_len); - len += ret; - } - SDEBUG("_send: %d %d\n", ret, len); - mutex_unlock(&send_lock); - -#ifdef MODULE_NETSTATS_L2 - netdev->stats.tx_bytes += len; -#endif - - if (ret < 0) { - return ret; - } - - return len; -} - -static int _recv(netdev_t *netdev, void *buf, size_t len, void *info) -{ - (void)info; - (void)netdev; - - int ret = _try_receive((char *)buf, len, 1); -#ifdef MODULE_NETSTATS_L2 - if (buf) { - netdev->stats.rx_count++; - netdev->stats.rx_bytes += len; - } -#endif - - SDEBUG("_recev: %d\n", ret); - - return ret; -} - -static int _get(netdev_t *dev, netopt_t opt, void *value, size_t max_len) -{ - int res = -1; - - switch (opt) { - case NETOPT_ADDRESS: - assert(max_len >= ETHERNET_ADDR_LEN); - get_mac((char *)value); - res = ETHERNET_ADDR_LEN; - break; - default: - res = netdev_eth_get(dev, opt, value, max_len); - break; - } - - return res; -} - -static int _set(netdev_t *dev, netopt_t opt, const void *value, size_t max_len) -{ - int res = -1; - - switch (opt) { - case NETOPT_ADDRESS: - assert(max_len >= ETHERNET_ADDR_LEN); - set_mac((char *)value); - res = ETHERNET_ADDR_LEN; - break; - default: - res = netdev_eth_set(dev, opt, value, max_len); - break; - } - - return res; -} - -static int _init(netdev_t *netdev) -{ - return eth_init(); -} - -const static netdev_driver_t netdev_driver_stm32f4eth = { - .send = _send, - .recv = _recv, - .init = _init, - .isr = _isr, - .get = _get, - .set = _set, -}; - -void eth_netdev_setup(netdev_t *netdev) -{ - _netdev = netdev; - netdev->driver = &netdev_driver_stm32f4eth; -} - #endif diff --git a/cpu/stm32f4/include/periph_cpu.h b/cpu/stm32f4/include/periph_cpu.h index 4a09f52970b6..5faead9535bf 100644 --- a/cpu/stm32f4/include/periph_cpu.h +++ b/cpu/stm32f4/include/periph_cpu.h @@ -84,122 +84,6 @@ typedef struct { uint8_t chan; /**< CPU ADC channel connected to the pin */ } adc_conf_t; -/** - * @brief Ethernet Peripheral configuration - */ -typedef struct { - enum { - MII = 18, /**< Configuration for MII */ - RMII = 9, /**< Configuration for RMII */ - SMI = 2, /**< Configuration for SMI */ - } mode; /**< Select configuration mode */ - enum { - ETH_SPEED_10T_HD = 0x0000, - ETH_SPEED_10T_FD = 0x0100, - ETH_SPEED_100TX_HD = 0x2000, - ETH_SPEED_100TX_FD = 0x2100, - } speed; /**< Speed selection */ - uint8_t dma_stream; /**< DMA stream used for TX */ - uint8_t dma_chan; /**< DMA channel used for TX */ - char mac[6]; /**< Et hernet MAC address */ - char phy_addr; /**< PHY address */ - gpio_t pins[]; /**< Pins to use. MII requires 18 pins, - RMII 9 and SMI 9. Not all speeds are - supported by all modes. */ -} eth_conf_t; - -/** - * @brief Power on the DMA device the given stream belongs to - * - * @param[in] stream logical DMA stream - */ -static inline void dma_poweron(int stream) -{ - if (stream < 8) { - periph_clk_en(AHB1, RCC_AHB1ENR_DMA1EN); - } - else { - periph_clk_en(AHB1, RCC_AHB1ENR_DMA2EN); - } -} - -/** - * @brief Get DMA base register - * - * For simplifying DMA stream handling, we map the DMA channels transparently to - * one integer number, such that DMA1 stream0 equals 0, DMA2 stream0 equals 8, - * DMA2 stream 7 equals 15 and so on. - * - * @param[in] stream logical DMA stream - */ -static inline DMA_TypeDef *dma_base(int stream) -{ - return (stream < 8) ? DMA1 : DMA2; -} - -/** - * @brief Get the DMA stream base address - * - * @param[in] stream logical DMA stream - * - * @return base address for the selected DMA stream - */ -static inline DMA_Stream_TypeDef *dma_stream(int stream) -{ - uint32_t base = (uint32_t)dma_base(stream); - - return (DMA_Stream_TypeDef *)(base + (0x10 + (0x18 * (stream & 0x7)))); -} - -/** - * @brief Select high or low DMA interrupt register based on stream number - * - * @param[in] stream logical DMA stream - * - * @return 0 for streams 0-3, 1 for streams 3-7 - */ -static inline int dma_hl(int stream) -{ - return ((stream & 0x4) >> 2); -} - -/** - * @brief Get the interrupt flag clear bit position in the DMA LIFCR register - * - * @param[in] stream logical DMA stream - */ -static inline uint32_t dma_ifc(int stream) -{ - switch (stream & 0x3) { - case 0: - return (1 << 5); - case 1: - return (1 << 11); - case 2: - return (1 << 21); - case 3: - return (1 << 27); - default: - return 0; - } -} - -static inline void dma_isr_enable(int stream) -{ - if (stream < 7) { - NVIC_EnableIRQ((IRQn_Type)((int)DMA1_Stream0_IRQn + stream)); - } - else if (stream == 7) { - NVIC_EnableIRQ(DMA1_Stream7_IRQn); - } - else if (stream < 13) { - NVIC_EnableIRQ((IRQn_Type)((int)DMA2_Stream0_IRQn + (stream - 8))); - } - else if (stream < 16) { - NVIC_EnableIRQ((IRQn_Type)((int)DMA2_Stream5_IRQn + (stream - 13))); - } -} - #ifdef __cplusplus } #endif diff --git a/drivers/Makefile.dep b/drivers/Makefile.dep index edb24663674a..a328eb2b499f 100644 --- a/drivers/Makefile.dep +++ b/drivers/Makefile.dep @@ -477,6 +477,14 @@ ifneq (,$(filter srf08,$(USEMODULE))) USEMODULE += xtimer endif +ifneq (,$(filter stm32_eth,$(USEMODULE))) + FEATURES_REQUIRED += periph_eth + FEATURES_REQUIRED += periph_dma + USEMODULE += netdev_eth + USEMODULE += iolist + USEMODULE += luid +endif + ifneq (,$(filter sx127%,$(USEMODULE))) FEATURES_REQUIRED += periph_gpio FEATURES_REQUIRED += periph_gpio_irq diff --git a/drivers/include/net/phy.h b/drivers/include/net/phy.h deleted file mode 100644 index 18aae066e925..000000000000 --- a/drivers/include/net/phy.h +++ /dev/null @@ -1,134 +0,0 @@ -/* - * Copyright (C) 2016 TriaGnoSys GmbH - * - * This file is subject to the terms and conditions of the GNU Lesser General - * Public License v2.1. See the file LICENSE in the top level directory for - * more details. - */ - -/** - * @defgroup ethernet_phy Ethernet PHY - * @brief Provides a Ethernet PHY abstraction - * @{ - * - * @file - * @brief Definitions for Ethernet PHY devices - * - * @author Víctor Ariño - */ - -#ifndef ETH_PHY_H -#define ETH_PHY_H - -#ifdef __cplusplus -extern "C" { -#endif - -#include - -/* Ethernet PHY Common Registers */ -#define PHY_BMCR (0x00) -#define PHY_BSMR (0x01) -#define PHY_PHYIDR1 (0x02) -#define PHY_PHYIDR2 (0x03) -#define PHY_ANAR (0x04) -#define PHY_ANLPAR (0x05) -#define PHY_ANER (0x06) -#define PHY_ANNPTR (0x07) - -/* Ethernet PHY BMCR Fields */ -#define BMCR_RESET (0x8000) -#define BMCR_LOOPBACK (0x4000) -#define BMCR_SPEED_SELECT (0x2000) -#define BMCR_AN (0x1000) -#define BMCR_POWER_DOWN (0x0800) -#define BMCR_ISOLATE (0x0400) -#define BMCR_RESTART_AN (0x0200) -#define BMCR_DUPLEX_MODE (0x0100) -#define BMCR_COLLISION_TEST (0x0080) - -/* Ethernet PHY BSMR Fields */ -#define BSMR_100BASE_T4 (0x8000) -#define BSMR_100BASE_TX_FDUPLEX (0x4000) -#define BSMR_100BASE_TX_HDUPLEX (0x2000) -#define BSMR_10BASE_T_FDUPLEX (0x1000) -#define BSMR_10BASE_T_HDUPLEX (0x0800) -#define BSMR_NO_PREAMBLE (0x0040) -#define BSMR_AN_COMPLETE (0x0020) -#define BSMR_REMOTE_FAULT (0x0010) -#define BSMR_AN_ABILITY (0x0008) -#define BSMR_LINK_STATUS (0x0004) -#define BSMR_JABBER_DETECT (0x0002) -#define BSMR_EXTENDED_CAP (0x0001) - -/* Ethernet PHY PHYIDR1 Fields */ -#define PHYIDR1_OUI (0xffff) - -/* Ethernet PHY PHYIDR2 Fields */ -#define PHYIDR2_OUI (0xfe00) -#define PHYIDR2_MODEL (0x01f0) -#define PHYIDR2_REV (0x0007) - -/* Ethernet PHY ANAR Fields */ -#define ANAR_NEXT_PAGE (0x8000) -#define ANAR_REMOTE_FAULT (0x2000) -#define ANAR_PAUSE (0x0600) -#define ANAR_100BASE_T4 (0x0200) -#define ANAR_100BASE_TX_FDUPLEX (0x0100) -#define ANAR_100BASE_TX_HDUPLEX (0x0080) -#define ANAR_10BASE_T_FDUPLEX (0x0040) -#define ANAR_10BASE_T_HDUPLEX (0x0020) -#define ANAR_SELECTOR (0x000f) - -/* Ethernet PHY ANLPAR Fields */ -#define ANLPAR_NEXT_PAGE (0x8000) -#define ANLPAR_ACK (0x4000) -#define ANLPAR_REMOTE_FAULT (0x2000) -#define ANLPAR_PAUSE (0x0600) -#define ANLPAR_100BASE_T4 (0x0200) -#define ANLPAR_100BASE_TX_FDUPLEX (0x0100) -#define ANLPAR_100BASE_TX_HDUPLEX (0x0080) -#define ANLPAR_10BASE_T_FDUPLEX (0x0040) -#define ANLPAR_10BASE_T_HDUPLEX (0x0020) -#define ANLPAR_SELECTOR (0x000f) - -/* Ethernet PHY ANNPTR Fields */ -#define ANNPTR_NEXT_PAGE (0x8000) -#define ANNPTR_MSG_PAGE (0x2000) -#define ANNPTR_ACK2 (0x1000) -#define ANNPTR_TOGGLE_TX (0x0800) -#define ANNPTR_CODE (0x03ff) - -/* Ethernet PHY ANER Fields */ -#define ANER_PDF (0x0010) -#define ANER_LP_NEXT_PAGE_ABLE (0x0008) -#define ANER_NEXT_PAGE_ABLE (0x0004) -#define ANER_PAGE_RX (0x0002) -#define ANER_LP_AN_ABLE (0x0001) - -/** - * @brief Read a PHY register - * - * @param[in] addr address of the PHY to read - * @param[in] reg register to be read - * - * @return value in the register, or <=0 on error - */ -int32_t eth_phy_read(uint16_t addr, uint8_t reg); - -/** - * @brief Write a PHY register - * - * @param[in] addr address of the PHY to write - * @param[in] reg register to be written - * @param[in] value value to write into the register - * - * @return 0 in case of success or <=0 on error - */ -int32_t eth_phy_write(uint16_t addr, uint8_t reg, uint16_t value); - -#ifdef __cplusplus -} -#endif -/** @} */ -#endif /* ETH_PHY_H */ diff --git a/drivers/include/stm32_eth.h b/drivers/include/stm32_eth.h new file mode 100644 index 000000000000..bb91d38cbd2d --- /dev/null +++ b/drivers/include/stm32_eth.h @@ -0,0 +1,31 @@ +/* + * + * @file + * @brief Interface definition for the stm32 ethernet driver + * + * @author Robin Lösch + * + * @{ + */ + +#ifndef STM32_ETH_H +#define STM32_ETH_H + +#include "net/netdev.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief Setup netdev + * + */ +void stm32_eth_netdev_setup(netdev_t *netdev); + +#ifdef __cplusplus +} +#endif + +#endif /* STM32_ETH_H */ +/* @} */ diff --git a/drivers/stm32_eth/Makefile b/drivers/stm32_eth/Makefile new file mode 100644 index 000000000000..48422e909a47 --- /dev/null +++ b/drivers/stm32_eth/Makefile @@ -0,0 +1 @@ +include $(RIOTBASE)/Makefile.base diff --git a/drivers/stm32_eth/doc.txt b/drivers/stm32_eth/doc.txt new file mode 100644 index 000000000000..0bff9e38df41 --- /dev/null +++ b/drivers/stm32_eth/doc.txt @@ -0,0 +1,13 @@ +/* + * + * This file is subject to the terms and conditions of the GNU Lesser + * General Public License v2.1. See the file LICENSE in the top level + * directory for more details. + */ + +/** +@defgroup drivers_stm32_common Driver for stm32 ethernet +@ingroup drivers_netdev +@brief Device Driver for STM32 Ethernet + +*/ diff --git a/drivers/stm32_eth/stm32_eth.c b/drivers/stm32_eth/stm32_eth.c new file mode 100644 index 000000000000..45773e2d7408 --- /dev/null +++ b/drivers/stm32_eth/stm32_eth.c @@ -0,0 +1,157 @@ +/* + * Copyright (C) 2016 TriaGnoSys GmbH + * + * This file is subject to the terms and conditions of the GNU Lesser General + * Public License v2.1. See the file LICENSE in the top level directory for more + * details. + */ + +/** + * @ingroup drivers_stm32_common + * @{ + * + * @file + * @brief Netdev wrapper for stm32 ethernet + * + * @author Víctor Ariño + * + * @} + */ + +#include "periph_conf.h" +#include "mutex.h" +#include "net/netdev/eth.h" +#include "net/ethernet.h" +#include "iolist.h" +#define ENABLE_DEBUG (0) +#include "debug.h" + +#include +static mutex_t _tx = MUTEX_INIT; +static mutex_t _rx = MUTEX_INIT; +netdev_t *_netdev; + +void stm32_eth_set_mac(const char *mac); +void stm32_eth_get_mac(char *out); +int stm32_eth_init(void); +int stm32_eth_receive_blocking(char *data, unsigned max_len); +int stm32_eth_send(const struct iolist *iolist); +int stm32_eth_get_rx_status_owned(void); + +static void _isr(netdev_t *netdev) { + if(stm32_eth_get_rx_status_owned()) { + netdev->event_callback(netdev, NETDEV_EVENT_RX_COMPLETE); + } +} + +void isr_eth(void) +{ + volatile unsigned tmp = ETH->DMASR; + + if ((tmp & ETH_DMASR_TS)) { + ETH->DMASR = ETH_DMASR_TS | ETH_DMASR_NIS; + mutex_unlock(&_tx); + } + + if ((tmp & ETH_DMASR_RS)) { + ETH->DMASR = ETH_DMASR_RS | ETH_DMASR_NIS; + mutex_unlock(&_rx); + if (_netdev) { + _netdev->event_callback(_netdev, NETDEV_EVENT_ISR); + } + } + + /* printf("r:%x\n\n", tmp); */ + + cortexm_isr_end(); +} + +static int _recv(netdev_t *netdev, void *buf, size_t len, void *info) +{ + (void)info; + (void)netdev; + if(!stm32_eth_get_rx_status_owned()){ + mutex_lock(&_rx); + } + int ret = stm32_eth_receive_blocking((char *)buf, len); + DEBUG("stm32_eth_netdev: _recev: %d\n", ret); + + return ret; +} + +static int _send(netdev_t *netdev, const struct iolist *iolist) +{ + (void)netdev; + int ret = 0; + if(stm32_eth_get_rx_status_owned()) { + mutex_lock(&_tx); + } + netdev->event_callback(netdev, NETDEV_EVENT_TX_STARTED); + ret = stm32_eth_send(iolist); + DEBUG("stm32_eth_netdev: _send: %d %d\n", ret, iolist_size(iolist)); + if (ret < 0) + { + netdev->event_callback(netdev, NETDEV_EVENT_TX_MEDIUM_BUSY); + return ret; + } + netdev->event_callback(netdev, NETDEV_EVENT_TX_COMPLETE); + + return ret; +} + +static int _set(netdev_t *dev, netopt_t opt, const void *value, size_t max_len) +{ + int res = -1; + + switch (opt) { + case NETOPT_ADDRESS: + assert(max_len >= ETHERNET_ADDR_LEN); + stm32_eth_set_mac((char *)value); + res = ETHERNET_ADDR_LEN; + break; + default: + res = netdev_eth_set(dev, opt, value, max_len); + break; + } + + return res; +} + +static int _get(netdev_t *dev, netopt_t opt, void *value, size_t max_len) +{ + int res = -1; + + switch (opt) { + case NETOPT_ADDRESS: + assert(max_len >= ETHERNET_ADDR_LEN); + stm32_eth_get_mac((char *)value); + res = ETHERNET_ADDR_LEN; + break; + default: + res = netdev_eth_get(dev, opt, value, max_len); + break; + } + + return res; +} + +static int _init(netdev_t *netdev) +{ + (void)netdev; + return stm32_eth_init(); +} + +static const netdev_driver_t netdev_driver_stm32f4eth = { + .send = _send, + .recv = _recv, + .init = _init, + .isr = _isr, + .get = _get, + .set = _set, +}; + +void stm32_eth_netdev_setup(netdev_t *netdev) +{ + _netdev = netdev; + netdev->driver = &netdev_driver_stm32f4eth; +} \ No newline at end of file diff --git a/sys/auto_init/auto_init.c b/sys/auto_init/auto_init.c index 8a75f881c6ec..dba857606724 100644 --- a/sys/auto_init/auto_init.c +++ b/sys/auto_init/auto_init.c @@ -191,6 +191,11 @@ void auto_init(void) /* initialize network devices */ #ifdef MODULE_AUTO_INIT_GNRC_NETIF +#ifdef MODULE_STM32_ETH + extern void auto_init_stm32_eth(void); + auto_init_stm32_eth(); +#endif + #ifdef MODULE_AT86RF2XX extern void auto_init_at86rf2xx(void); auto_init_at86rf2xx(); diff --git a/sys/auto_init/netif/auto_init_stm32_eth.c b/sys/auto_init/netif/auto_init_stm32_eth.c new file mode 100644 index 000000000000..90096922f244 --- /dev/null +++ b/sys/auto_init/netif/auto_init_stm32_eth.c @@ -0,0 +1,30 @@ +/** + * @ingroup sys_auto_init_gnrc_netif + * @{ + * + * @brief Auto initzialize stm32 ethernet driver + * + * @author Robin Lösch + */ + +#ifdef MODULE_STM32_ETH + +#include "stm32_eth.h" +#include "net/gnrc/netif/ethernet.h" + +static netdev_t stm32eth; +static char stack[THREAD_STACKSIZE_DEFAULT]; + +void auto_init_stm32_eth(void) +{ + /* setup netdev device */ + stm32_eth_netdev_setup(&stm32eth); + /* initialize netdev <-> gnrc adapter state */ + gnrc_netif_ethernet_create(stack, THREAD_STACKSIZE_DEFAULT, GNRC_NETIF_PRIO, "stm32_eth", + &stm32eth); +} + +#else +typedef int dont_be_pedantic; +#endif /* MODULE_STM32_ETH */ +/** @} */ diff --git a/tests/stm32_eth_lwip/Makefile b/tests/stm32_eth_lwip/Makefile deleted file mode 100644 index e6da89c523f7..000000000000 --- a/tests/stm32_eth_lwip/Makefile +++ /dev/null @@ -1,17 +0,0 @@ -APPLICATION = stm32_eth_lwip -include ../Makefile.tests_common - -BOARD := stm32f4discovery - -FEATURES_REQUIRED += periph_stm32_eth - -USEMODULE += lwip -USEMODULE += lwip_netdev -USEMODULE += lwip_udp -USEMODULE += lwip_sock_udp -USEMODULE += lwip_ethernet -USEMODULE += lwip_ipv4 -USEMODULE += lwip_arp -USEMODULE += netdev_eth - -include $(RIOTBASE)/Makefile.include diff --git a/tests/stm32_eth_lwip/README.md b/tests/stm32_eth_lwip/README.md deleted file mode 100644 index 97eda3b77e07..000000000000 --- a/tests/stm32_eth_lwip/README.md +++ /dev/null @@ -1,21 +0,0 @@ -Tests for stm32 Ethernet periph driver -====================================== - -This tests the stm32 Ethernet driver using lwIP and IPv4. It implements a very -simple UDP echo server at the configured address (by default 172.16.19.5) and -port `12345`. - -To interface with the board configure the local IP address of the available -interface (e.g. eth1) with the gateway address (by default 172.16.19.1) -and execute a tool such as netcat to send UPD messages to the stm32. - -```sh -# Configure IP on the available interface -ifconfig eth1 172.16.19.1/24 - -# Start netcat -nc -u 172.16.19.5 12345 -``` - -The board will reply all the messages sent to it (with a maximum length of 128 -bytes). diff --git a/tests/stm32_eth_lwip/main.c b/tests/stm32_eth_lwip/main.c deleted file mode 100644 index 390273c12e3e..000000000000 --- a/tests/stm32_eth_lwip/main.c +++ /dev/null @@ -1,85 +0,0 @@ -/* - * Copyright (C) 2017 TriaGnoSys GmbH - * - * This file is subject to the terms and conditions of the GNU Lesser - * General Public License v2.1. See the file LICENSE in the top level - * directory for more details. - */ - -/** - * @{ - * - * @file - * @brief Show case application for stm32 eth driver - * - * @author Víctor Ariño - * - * @} - */ - -#include - -#include "net/netdev.h" -#include "net/netdev/eth.h" -#include "net/sock/udp.h" -#include "net/sock/udp.h" -#include "net/phy.h" - -#include "lwip.h" -#include "lwip/netif.h" -#include "lwip/netif/netdev.h" - -#include "xtimer.h" - -#define SET_IP(x, ...) IP4_ADDR(x, __VA_ARGS__) - -static netdev_t stm32f4eth; -static struct netif netif; -static ip4_addr_t local_ip, netmask, gw; -static sock_udp_ep_t local = SOCK_IPV4_EP_ANY; -static sock_udp_ep_t remote; -static uint8_t buff[128]; - -void eth_netdev_setup(netdev_t *netdev); - -int main(void) -{ - puts("Booting"); - - eth_netdev_setup(&stm32f4eth); - - SET_IP(&local_ip, 172, 16, 19, 5); - SET_IP(&netmask, 255, 255, 255, 0); - SET_IP(&gw, 172, 16, 19, 1); - - if (netif_add(&netif, &local_ip, &netmask, &gw, &stm32f4eth, - lwip_netdev_init, tcpip_input) == NULL) { - puts("error netif_add"); - return -1; - } - else if (netif.state != NULL) { - netif_set_default(&netif); - } - - sock_udp_t sock; - local.port = 12345; - - if (sock_udp_create(&sock, &local, NULL, 0) < 0) { - puts("Error creating UDP sock"); - return 1; - } - - puts("Waiting for messages..."); - while (1) { - ssize_t res; - if ((res = sock_udp_recv(&sock, buff, sizeof(buff), SOCK_NO_TIMEOUT, - &remote)) >= 0) { - puts("Received a message"); - if (sock_udp_send(&sock, buff, res, &remote) < 0) { - puts("Error sending reply"); - } - } - } - - return 0; -} From 9e6d5585967d7f50ad9b44061772a9f360770237 Mon Sep 17 00:00:00 2001 From: Alexandre Abadie Date: Tue, 21 May 2019 15:47:17 +0200 Subject: [PATCH 3/3] stm32_eth: Code cleanup and some fixes cpu/stm32_common: cleanup periph eth boards/nucleo-f767zi: cleanup dependencies boards/nucleo-f767zi: fix dma configuration attribute for eth examples/default: add nucleo-767zi in boards with netif drivers/stm_32_eth: Add header guard for eth_config Co-authored-By: Robin --- boards/nucleo-f767zi/Makefile.features | 1 - boards/nucleo-f767zi/include/periph_conf.h | 25 +++++----- cpu/stm32_common/include/periph_cpu_common.h | 47 ++++++++++-------- cpu/stm32_common/periph/eth.c | 50 ++++++++++---------- drivers/stm32_eth/stm32_eth.c | 2 +- examples/default/Makefile | 2 +- 6 files changed, 68 insertions(+), 59 deletions(-) diff --git a/boards/nucleo-f767zi/Makefile.features b/boards/nucleo-f767zi/Makefile.features index abd111b99428..1fec6ceb1298 100644 --- a/boards/nucleo-f767zi/Makefile.features +++ b/boards/nucleo-f767zi/Makefile.features @@ -7,7 +7,6 @@ FEATURES_PROVIDED += periph_spi FEATURES_PROVIDED += periph_timer FEATURES_PROVIDED += periph_uart FEATURES_PROVIDED += periph_eth -FEATURES_PROVIDED += periph_stm32_eth # load the common Makefile.features for Nucleo boards include $(RIOTBOARD)/common/nucleo144/Makefile.features diff --git a/boards/nucleo-f767zi/include/periph_conf.h b/boards/nucleo-f767zi/include/periph_conf.h index e80f8c31d390..29237d3f8705 100644 --- a/boards/nucleo-f767zi/include/periph_conf.h +++ b/boards/nucleo-f767zi/include/periph_conf.h @@ -40,7 +40,7 @@ static const dma_conf_t dma_config[] = { { .stream = 4 }, /* DMA1 Stream 4 - USART3_TX */ { .stream = 14 }, /* DMA2 Stream 6 - USART6_TX */ { .stream = 6 }, /* DMA1 Stream 6 - USART2_TX */ - { .stream = 8 }, /* DMA2 Stream 8 - ETH_TX */ + { .stream = 8 }, /* DMA2 Stream 0 - ETH_TX */ }; #define DMA_0_ISR isr_dma1_stream4 @@ -160,26 +160,16 @@ static const spi_conf_t spi_config[] = { #define SPI_NUMOF (sizeof(spi_config) / sizeof(spi_config[0])) /** @} */ - /** * @name ETH configuration * @{ */ -#define ETH_NUMOF (1) -#define ETH_RX_BUFFER_COUNT (4) -#define ETH_TX_BUFFER_COUNT (4) - -#define ETH_RX_BUFFER_SIZE (1524) -#define ETH_TX_BUFFER_SIZE (1524) - -#define ETH_DMA_ISR isr_dma2_stream0 - static const eth_conf_t eth_config = { .mode = RMII, .mac = { 0 }, .speed = ETH_SPEED_100TX_FD, - .dma_chan = 0, - .dma_stream = 8, + .dma = 3, + .dma_chan = 8, .phy_addr = 0x01, .pins = { GPIO_PIN(PORT_G, 13), @@ -193,6 +183,15 @@ static const eth_conf_t eth_config = { GPIO_PIN(PORT_A, 1), } }; + +#define ETH_RX_BUFFER_COUNT (4) +#define ETH_TX_BUFFER_COUNT (4) + +#define ETH_RX_BUFFER_SIZE (1524) +#define ETH_TX_BUFFER_SIZE (1524) + +#define ETH_DMA_ISR isr_dma2_stream0 + /** @} */ #ifdef __cplusplus diff --git a/cpu/stm32_common/include/periph_cpu_common.h b/cpu/stm32_common/include/periph_cpu_common.h index f8f58836b180..2a2123d3abab 100644 --- a/cpu/stm32_common/include/periph_cpu_common.h +++ b/cpu/stm32_common/include/periph_cpu_common.h @@ -708,30 +708,38 @@ int dma_configure(dma_t dma, int chan, const volatile void *src, volatile void * #include "candev_stm32.h" #endif -#ifdef MODULE_STM32_ETH +/** + * @brief STM32 Ethernet configuration mode + */ +typedef enum { + MII = 18, /**< Configuration for MII */ + RMII = 9, /**< Configuration for RMII */ + SMI = 2, /**< Configuration for SMI */ +} eth_mode_t; + +/** + * @brief STM32 Ethernet speed options + */ +typedef enum { + ETH_SPEED_10T_HD = 0x0000, + ETH_SPEED_10T_FD = 0x0100, + ETH_SPEED_100TX_HD = 0x2000, + ETH_SPEED_100TX_FD = 0x2100, +} eth_speed_t; /** * @brief Ethernet Peripheral configuration */ typedef struct { - enum { - MII = 18, /**< Configuration for MII */ - RMII = 9, /**< Configuration for RMII */ - SMI = 2, /**< Configuration for SMI */ - } mode; /**< Select configuration mode */ - enum { - ETH_SPEED_10T_HD = 0x0000, - ETH_SPEED_10T_FD = 0x0100, - ETH_SPEED_100TX_HD = 0x2000, - ETH_SPEED_100TX_FD = 0x2100, - } speed; /**< Speed selection */ - uint8_t dma; /**< Locical CMA Descriptor used for TX */ - uint8_t dma_chan; /**< DMA channel used for TX */ - char mac[6]; /**< Et hernet MAC address */ - char phy_addr; /**< PHY address */ - gpio_t pins[]; /**< Pins to use. MII requires 18 pins, - RMII 9 and SMI 9. Not all speeds are - supported by all modes. */ + eth_mode_t mode; /**< Select configuration mode */ + char mac[6]; /**< Ethernet MAC address */ + eth_speed_t speed; /**< Speed selection */ + uint8_t dma; /**< Locical CMA Descriptor used for TX */ + uint8_t dma_chan; /**< DMA channel used for TX */ + char phy_addr; /**< PHY address */ + gpio_t pins[]; /**< Pins to use. MII requires 18 pins, + RMII 9 and SMI 9. Not all speeds are + supported by all modes. */ } eth_conf_t; /** @@ -848,6 +856,7 @@ typedef struct { #define ANER_LP_AN_ABLE (0x0001) /** @} */ +#ifdef MODULE_STM32_ETH /** * @brief Read a PHY register * diff --git a/cpu/stm32_common/periph/eth.c b/cpu/stm32_common/periph/eth.c index 1225c78c8abf..0fb9728a6994 100644 --- a/cpu/stm32_common/periph/eth.c +++ b/cpu/stm32_common/periph/eth.c @@ -7,7 +7,7 @@ */ /** - * @ingroup cpu_stm32f4 + * @ingroup cpu_stm32_common * @{ * * @file @@ -17,16 +17,20 @@ * * @} */ +#include + #include "mutex.h" -#include "periph/gpio.h" #include "luid.h" -#include "net/ethernet.h" + #include "iolist.h" +#include "net/ethernet.h" + +#include "periph/gpio.h" + #define ENABLE_DEBUG (0) #include "debug.h" -#include -#if ETH_NUMOF + /* Set the value of the divider with the clock configured */ #if !defined(CLOCK_CORECLOCK) || CLOCK_CORECLOCK < (20000000U) #error This peripheral requires a CORECLOCK of at least 20MHz @@ -83,7 +87,7 @@ static unsigned _rw_phy(unsigned addr, unsigned reg, unsigned value) { unsigned tmp; - while (ETH->MACMIIAR & ETH_MACMIIAR_MB) ; + while (ETH->MACMIIAR & ETH_MACMIIAR_MB) {} DEBUG("stm32_eth: rw_phy %x (%x): %x\n", addr, reg, value); tmp = (ETH->MACMIIAR & ETH_MACMIIAR_CR) | ETH_MACMIIAR_MB; @@ -92,7 +96,7 @@ static unsigned _rw_phy(unsigned addr, unsigned reg, unsigned value) ETH->MACMIIDR = (value & 0xffff); ETH->MACMIIAR = tmp; - while (ETH->MACMIIAR & ETH_MACMIIAR_MB) ; + while (ETH->MACMIIAR & ETH_MACMIIAR_MB) {} DEBUG("stm32_eth: %lx\n", ETH->MACMIIDR); return (ETH->MACMIIDR & 0x0000ffff); @@ -150,10 +154,11 @@ static void _init_buffer(void) for (i = 0; i < ETH_TX_BUFFER_COUNT; i++) { tx_desc[i].status = TX_DESC_TCH | TX_DESC_CIC; tx_desc[i].buffer_addr = &tx_buffer[i][0]; - if((i+1) < ETH_RX_BUFFER_COUNT) { + if ((i + 1) < ETH_RX_BUFFER_COUNT) { tx_desc[i].desc_next = &tx_desc[i + 1]; } } + tx_desc[i - 1].desc_next = &tx_desc[0]; rx_curr = &rx_desc[0]; @@ -181,8 +186,8 @@ int stm32_eth_init(void) } /* enable all clocks */ - RCC->AHB1ENR |= (RCC_AHB1ENR_ETHMACEN | RCC_AHB1ENR_ETHMACTXEN - | RCC_AHB1ENR_ETHMACRXEN | RCC_AHB1ENR_ETHMACPTPEN); + RCC->AHB1ENR |= (RCC_AHB1ENR_ETHMACEN | RCC_AHB1ENR_ETHMACTXEN | + RCC_AHB1ENR_ETHMACRXEN | RCC_AHB1ENR_ETHMACPTPEN); /* reset the peripheral */ RCC->AHB1RSTR |= RCC_AHB1RSTR_ETHMACRST; @@ -190,10 +195,10 @@ int stm32_eth_init(void) /* software reset */ ETH->DMABMR |= ETH_DMABMR_SR; - while (ETH->DMABMR & ETH_DMABMR_SR) ; + while (ETH->DMABMR & ETH_DMABMR_SR) {} /* set the clock divider */ - while (ETH->MACMIIAR & ETH_MACMIIAR_MB) ; + while (ETH->MACMIIAR & ETH_MACMIIAR_MB) {} ETH->MACMIIAR = CLOCK_RANGE; /* configure the PHY (standard for all PHY's) */ @@ -208,18 +213,19 @@ int stm32_eth_init(void) /* pass all */ //ETH->MACFFR |= ETH_MACFFR_RA; /* perfect filter on address */ - ETH->MACFFR |= ETH_MACFFR_PAM | ETH_MACFFR_DAIF; + ETH->MACFFR |= (ETH_MACFFR_PAM | ETH_MACFFR_DAIF); /* store forward */ - ETH->DMAOMR |= ETH_DMAOMR_RSF | ETH_DMAOMR_TSF | ETH_DMAOMR_OSF; + ETH->DMAOMR |= (ETH_DMAOMR_RSF | ETH_DMAOMR_TSF | ETH_DMAOMR_OSF); /* configure DMA */ - ETH->DMABMR = ETH_DMABMR_DA | ETH_DMABMR_AAB | ETH_DMABMR_FB | - ETH_DMABMR_RDP_32Beat | ETH_DMABMR_PBL_32Beat | ETH_DMABMR_EDE; + ETH->DMABMR = (ETH_DMABMR_DA | ETH_DMABMR_AAB | ETH_DMABMR_FB | + ETH_DMABMR_RDP_32Beat | ETH_DMABMR_PBL_32Beat | ETH_DMABMR_EDE); if(eth_config.mac[0] != 0) { stm32_eth_set_mac(eth_config.mac); - } else { + } + else { luid_get(hwaddr, ETHERNET_ADDR_LEN); stm32_eth_set_mac(hwaddr); } @@ -264,8 +270,7 @@ int stm32_eth_send(const struct iolist *iolist) tx_curr->status &= 0x0fffffff; dma_acquire(eth_config.dma); - for (; iolist; iolist = iolist->iol_next) - { + for (; iolist; iolist = iolist->iol_next) { ret += dma_transfer(eth_config.dma, eth_config.dma_chan, iolist->iol_base, tx_curr->buffer_addr+ret, iolist->iol_len, DMA_MEM_TO_MEM, DMA_INC_BOTH_ADDR); } @@ -295,14 +300,13 @@ static int _try_receive(char *data, int max_len, int block) int copy, len = 0; int copied = 0; int drop = (data || max_len > 0); + edma_desc_t *p = rx_curr; for (int i = 0; i < ETH_RX_BUFFER_COUNT && len == 0; i++) { /* try receiving, if the block is set, simply wait for the rest of * the packet to complete, otherwise just break */ while (p->status & DESC_OWN) { - if (block) { - } - else { + if (!block) { break; } } @@ -354,5 +358,3 @@ void stm32_eth_isr_eth_wkup(void) { cortexm_isr_end(); } - -#endif diff --git a/drivers/stm32_eth/stm32_eth.c b/drivers/stm32_eth/stm32_eth.c index 45773e2d7408..34e868cac198 100644 --- a/drivers/stm32_eth/stm32_eth.c +++ b/drivers/stm32_eth/stm32_eth.c @@ -154,4 +154,4 @@ void stm32_eth_netdev_setup(netdev_t *netdev) { _netdev = netdev; netdev->driver = &netdev_driver_stm32f4eth; -} \ No newline at end of file +} diff --git a/examples/default/Makefile b/examples/default/Makefile index 430fca7f3936..87bca54625f8 100644 --- a/examples/default/Makefile +++ b/examples/default/Makefile @@ -39,7 +39,7 @@ USEMODULE += saul_default BOARD_PROVIDES_NETIF := acd52832 airfy-beacon b-l072z-lrwan1 cc2538dk fox \ iotlab-m3 iotlab-a8-m3 lobaro-lorabox lsn50 mulle microbit native nrf51dk \ - nrf51dongle nrf52dk nrf52840dk nrf52840-mdk nrf6310 \ + nrf51dongle nrf52dk nrf52840dk nrf52840-mdk nrf6310 nucleo-f767zi \ openmote-cc2538 pba-d-01-kw2x remote-pa remote-reva samr21-xpro \ spark-core telosb yunjia-nrf51822 z1