drivers: eth: add driver for w5500 Ethernet Controller

Add driver for w5500 Ethernet Controller

Signed-off-by: Parthiban Nallathambi <parthiban@linumiz.com>
This commit is contained in:
Parthiban Nallathambi 2020-09-02 10:36:48 +02:00 committed by Carles Cufí
commit c2ee9f5c3e
10 changed files with 783 additions and 1 deletions

View file

@ -183,7 +183,8 @@
/drivers/espi/ @albertofloyd @franciscomunoz @scottwcpg
/drivers/espi/*npcx* @MulinChao
/drivers/ethernet/ @jukkar @tbursztyka @pfalcon
/drivers/ethernet/*stm32* @Nukersson @lochej
/drivers/ethernet/*stm32* @Nukersson, @lochej
/drivers/ethernet/*w5500* @parthitce
/drivers/flash/ @nashif @nvlsianpu
/drivers/flash/*nrf* @nvlsianpu
/drivers/flash/*spi_nor* @pabigot

View file

@ -20,6 +20,7 @@ zephyr_sources_ifdef(CONFIG_ETH_MCUX eth_mcux.c)
zephyr_sources_ifdef(CONFIG_ETH_SMSC911X eth_smsc911x.c)
zephyr_sources_ifdef(CONFIG_ETH_STM32_HAL eth_stm32_hal.c)
zephyr_sources_ifdef(CONFIG_ETH_LITEETH eth_liteeth.c)
zephyr_sources_ifdef(CONFIG_ETH_W5500 eth_w5500.c)
if(CONFIG_ETH_NATIVE_POSIX)
zephyr_library()

View file

@ -55,5 +55,6 @@ source "drivers/ethernet/Kconfig.native_posix"
source "drivers/ethernet/Kconfig.stellaris"
source "drivers/ethernet/Kconfig.liteeth"
source "drivers/ethernet/Kconfig.gecko"
source "drivers/ethernet/Kconfig.w5500"
endmenu # "Ethernet Drivers"

View file

@ -0,0 +1,37 @@
# W5500 Ethernet driver configuration options
# Copyright (c) 2020 Linumiz
# Author: Parthiban Nallathambi <parthiban@linumiz.com>
# SPDX-License-Identifier: Apache-2.0
menuconfig ETH_W5500
bool "W5500 Ethernet Controller"
depends on SPI
help
W5500 Stand-Alone Ethernet Controller
with SPI Interface
config ETH_W5500_RX_THREAD_STACK_SIZE
int "Stack size for internal incoming packet handler"
depends on ETH_W5500
default 800
help
Size of the stack used for internal thread which is ran for
incoming packet processing.
config ETH_W5500_RX_THREAD_PRIO
int "Priority for internal incoming packet handler"
depends on ETH_W5500
default 2
help
Priority level for internal thread which is ran for incoming
packet processing.
config ETH_W5500_TIMEOUT
int "IP buffer timeout"
depends on ETH_W5500
default 100
help
Given timeout in milliseconds. Maximum amount of time
that the driver will wait from the IP stack to get
a memory buffer before the Ethernet frame is dropped.

View file

@ -0,0 +1,591 @@
/* W5500 Stand-alone Ethernet Controller with SPI
*
* Copyright (c) 2020 Linumiz
* Author: Parthiban Nallathambi <parthiban@linumiz.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
#define DT_DRV_COMPAT wiznet_w5500
#include <logging/log.h>
LOG_MODULE_REGISTER(eth_w5500, CONFIG_ETHERNET_LOG_LEVEL);
#include <zephyr.h>
#include <device.h>
#include <string.h>
#include <errno.h>
#include <drivers/gpio.h>
#include <drivers/spi.h>
#include <net/net_pkt.h>
#include <net/net_if.h>
#include <net/ethernet.h>
#include <ethernet/eth_stats.h>
#include "eth.h"
#include "eth_w5500_priv.h"
#define WIZNET_OUI_B0 0x00
#define WIZNET_OUI_B1 0x08
#define WIZNET_OUI_B2 0xdc
#define W5500_SPI_BLOCK_SELECT(addr) (((addr) >> 16) & 0x1f)
#define W5500_SPI_READ_CONTROL(addr) (W5500_SPI_BLOCK_SELECT(addr) << 3)
#define W5500_SPI_WRITE_CONTROL(addr) \
((W5500_SPI_BLOCK_SELECT(addr) << 3) | BIT(2))
static int w5500_spi_read(const struct device *dev, uint32_t addr,
uint8_t *data, uint32_t len)
{
int ret;
struct w5500_runtime *ctx = dev->data;
/* 3 bytes as 0x010203 during command phase */
uint8_t tmp[len + 3];
uint8_t cmd[3] = {
addr >> 8,
addr,
W5500_SPI_READ_CONTROL(addr)
};
const struct spi_buf tx_buf = {
.buf = cmd,
.len = ARRAY_SIZE(cmd),
};
const struct spi_buf_set tx = {
.buffers = &tx_buf,
.count = 1,
};
const struct spi_buf rx_buf = {
.buf = tmp,
.len = ARRAY_SIZE(tmp),
};
const struct spi_buf_set rx = {
.buffers = &rx_buf,
.count = 1,
};
ret = spi_transceive(ctx->spi, &ctx->spi_cfg, &tx, &rx);
if (!ret) {
/* skip the default dummy 0x010203 */
memcpy(data, &tmp[3], len);
}
return ret;
}
static int w5500_spi_write(const struct device *dev, uint32_t addr,
uint8_t *data, uint32_t len)
{
int ret;
struct w5500_runtime *ctx = dev->data;
uint8_t cmd[3] = {
addr >> 8,
addr,
W5500_SPI_WRITE_CONTROL(addr),
};
const struct spi_buf tx_buf[2] = {
{
.buf = cmd,
.len = ARRAY_SIZE(cmd),
},
{
.buf = data,
.len = len,
},
};
const struct spi_buf_set tx = {
.buffers = tx_buf,
.count = ARRAY_SIZE(tx_buf),
};
ret = spi_write(ctx->spi, &ctx->spi_cfg, &tx);
return ret;
}
static int w5500_readbuf(const struct device *dev, uint16_t offset, uint8_t *buf,
int len)
{
uint32_t addr;
int remain = 0;
int ret;
const uint32_t mem_start = W5500_Sn_RX_MEM_START;
const uint16_t mem_size = W5500_RX_MEM_SIZE;
offset %= mem_size;
addr = mem_start + offset;
if (offset + len > mem_size) {
remain = (offset + len) % mem_size;
len = mem_size - offset;
}
ret = w5500_spi_read(dev, addr, buf, len);
if (ret || !remain) {
return ret;
}
return w5500_spi_read(dev, mem_start, buf + len, remain);
}
static int w5500_writebuf(const struct device *dev, uint16_t offset, uint8_t *buf,
int len)
{
uint32_t addr;
int ret = 0;
int remain = 0;
const uint32_t mem_start = W5500_Sn_TX_MEM_START;
const uint32_t mem_size = W5500_TX_MEM_SIZE;
offset %= mem_size;
addr = mem_start + offset;
if (offset + len > mem_size) {
remain = (offset + len) % mem_size;
len = mem_size - offset;
}
ret = w5500_spi_write(dev, addr, buf, len);
if (ret || !remain) {
return ret;
}
return w5500_spi_write(dev, mem_start, buf + len, remain);
}
static int w5500_command(const struct device *dev, uint8_t cmd)
{
uint8_t reg;
uint64_t end = z_timeout_end_calc(K_MSEC(100));
w5500_spi_write(dev, W5500_S0_CR, &cmd, 1);
do {
w5500_spi_read(dev, W5500_S0_CR, &reg, 1);
if (end - z_tick_get() <= 0) {
return -EIO;
}
k_msleep(1);
} while (reg != 0);
return 0;
}
static int w5500_tx(const struct device *dev, struct net_pkt *pkt)
{
struct w5500_runtime *ctx = dev->data;
uint16_t len = net_pkt_get_len(pkt);
uint16_t offset;
uint8_t off[2];
int ret;
w5500_spi_read(dev, W5500_S0_TX_WR, off, 2);
offset = sys_get_be16(off);
if (net_pkt_read(pkt, ctx->buf, len)) {
return -EIO;
}
ret = w5500_writebuf(dev, offset, ctx->buf, len);
if (ret < 0) {
return ret;
}
sys_put_be16(offset + len, off);
w5500_spi_write(dev, W5500_S0_TX_WR, off, 2);
w5500_command(dev, S0_CR_SEND);
if (k_sem_take(&ctx->tx_sem, K_MSEC(10))) {
return -EIO;
}
return 0;
}
static void w5500_rx(const struct device *dev)
{
uint8_t mask = 0;
uint8_t header[2];
uint8_t tmp[2];
uint16_t off;
uint16_t rx_len;
uint16_t rx_buf_len;
uint16_t read_len;
uint16_t reader;
struct net_buf *pkt_buf = NULL;
struct net_pkt *pkt;
struct w5500_runtime *ctx = dev->data;
const struct w5500_config *config = dev->config;
/* disable interrupt */
w5500_spi_write(dev, W5500_SIMR, &mask, 1);
w5500_spi_read(dev, W5500_S0_RX_RSR, tmp, 2);
rx_buf_len = sys_get_be16(tmp);
if (rx_buf_len == 0) {
return;
}
w5500_spi_read(dev, W5500_S0_RX_RD, tmp, 2);
off = sys_get_be16(tmp);
w5500_readbuf(dev, off, header, 2);
rx_len = sys_get_be16(header) - 2;
pkt = net_pkt_rx_alloc_with_buffer(ctx->iface, rx_len,
AF_UNSPEC, 0, K_MSEC(config->timeout));
if (!pkt) {
eth_stats_update_errors_rx(ctx->iface);
return;
}
pkt_buf = pkt->buffer;
read_len = rx_len;
reader = off + 2;
do {
size_t frag_len;
uint8_t *data_ptr;
size_t frame_len;
data_ptr = pkt_buf->data;
frag_len = net_buf_tailroom(pkt_buf);
if (read_len > frag_len) {
frame_len = frag_len;
} else {
frame_len = read_len;
}
w5500_readbuf(dev, reader, data_ptr, frame_len);
net_buf_add(pkt_buf, frame_len);
reader += frame_len;
read_len -= frame_len;
pkt_buf = pkt_buf->frags;
} while (read_len > 0);
if (net_recv_data(ctx->iface, pkt) < 0) {
net_pkt_unref(pkt);
}
sys_put_be16(off + 2 + rx_len, tmp);
w5500_spi_write(dev, W5500_S0_RX_RD, tmp, 2);
w5500_command(dev, S0_CR_RECV);
}
static void w5500_isr(const struct device *dev)
{
uint8_t ir;
uint8_t mask = 0;
struct w5500_runtime *ctx = dev->data;
while (true) {
k_sem_take(&ctx->int_sem, K_FOREVER);
w5500_spi_read(dev, W5500_S0_IR, &ir, 1);
if (!ir) {
goto done;
}
w5500_spi_write(dev, W5500_S0_IR, &ir, 1);
if (ir & S0_IR_SENDOK) {
k_sem_give(&ctx->tx_sem);
LOG_DBG("TX Done");
}
if (ir & S0_IR_RECV) {
w5500_rx(dev);
}
done:
/* enable interrupt */
mask = IR_S0;
w5500_spi_write(dev, W5500_SIMR, &mask, 1);
}
}
static void w5500_iface_init(struct net_if *iface)
{
const struct device *dev = net_if_get_device(iface);
struct w5500_runtime *ctx = dev->data;
net_if_set_link_addr(iface, ctx->mac_addr,
sizeof(ctx->mac_addr),
NET_LINK_ETHERNET);
if (!ctx->iface) {
ctx->iface = iface;
}
ethernet_init(iface);
}
static enum ethernet_hw_caps w5500_get_capabilities(const struct device *dev)
{
ARG_UNUSED(dev);
return ETHERNET_LINK_10BASE_T | ETHERNET_LINK_100BASE_T
#if defined(CONFIG_NET_PROMISCUOUS_MODE)
| ETHERNET_PROMISC_MODE
#endif
;
}
static int w5500_set_config(const struct device *dev,
enum ethernet_config_type type,
const struct ethernet_config *config)
{
uint8_t mode;
uint8_t mr = W5500_S0_MR_MF;
w5500_spi_read(dev, W5500_S0_MR, &mode, 1);
if (IS_ENABLED(CONFIG_NET_PROMISCUOUS_MODE) &&
type == ETHERNET_CONFIG_TYPE_PROMISC_MODE) {
if (config->promisc_mode) {
if (!(mode & W5500_S0_MR_MF))
return -EALREADY;
}
/* clear */
WRITE_BIT(mode, mr, 0);
} else {
if (mode & mr) {
return -EALREADY;
}
/* set */
WRITE_BIT(mode, mr, 1);
}
return w5500_spi_write(dev, W5500_S0_MR, &mode, 1);
}
static int w5500_hw_start(const struct device *dev)
{
uint8_t mode = S0_MR_MACRAW;
uint8_t mask = IR_S0;
w5500_spi_write(dev, W5500_S0_MR, &mode, 1);
w5500_command(dev, S0_CR_OPEN);
/* enable interrupt */
w5500_spi_write(dev, W5500_SIMR, &mask, 1);
return 0;
}
static int w5500_hw_stop(const struct device *dev)
{
uint8_t mask = 0;
/* disable interrupt */
w5500_spi_write(dev, W5500_SIMR, &mask, 1);
w5500_command(dev, S0_CR_CLOSE);
return 0;
}
static struct ethernet_api w5500_api_funcs = {
.iface_api.init = w5500_iface_init,
.get_capabilities = w5500_get_capabilities,
.set_config = w5500_set_config,
.start = w5500_hw_start,
.stop = w5500_hw_stop,
.send = w5500_tx,
};
static int w5500_hw_reset(const struct device *dev)
{
int ret;
uint8_t mask = 0;
uint8_t tmp = MR_RST;
ret = w5500_spi_write(dev, W5500_MR, &tmp, 1);
if (ret < 0) {
return ret;
}
k_msleep(5);
tmp = MR_PB;
w5500_spi_write(dev, W5500_MR, &tmp, 1);
/* disable interrupt */
return w5500_spi_write(dev, W5500_SIMR, &mask, 1);
}
static void w5500_gpio_callback(const struct device *dev,
struct gpio_callback *cb,
uint32_t pins)
{
struct w5500_runtime *ctx =
CONTAINER_OF(cb, struct w5500_runtime, gpio_cb);
k_sem_give(&ctx->int_sem);
}
static void w5500_set_macaddr(const struct device *dev)
{
struct w5500_runtime *ctx = dev->data;
/* override vendor bytes */
memset(ctx->mac_addr, '\0', sizeof(ctx->mac_addr));
ctx->mac_addr[0] = WIZNET_OUI_B0;
ctx->mac_addr[1] = WIZNET_OUI_B1;
ctx->mac_addr[2] = WIZNET_OUI_B2;
if (ctx->generate_mac) {
ctx->generate_mac(ctx->mac_addr);
}
w5500_spi_write(dev, W5500_SHAR, ctx->mac_addr, sizeof(ctx->mac_addr));
}
static void w5500_memory_configure(const struct device *dev)
{
int i;
uint8_t mem = 0x10;
/* Configure RX & TX memory to 16K */
w5500_spi_write(dev, W5500_Sn_RXMEM_SIZE(0), &mem, 1);
w5500_spi_write(dev, W5500_Sn_TXMEM_SIZE(0), &mem, 1);
mem = 0;
for (i = 1; i < 8; i++) {
w5500_spi_write(dev, W5500_Sn_RXMEM_SIZE(i), &mem, 1);
w5500_spi_write(dev, W5500_Sn_TXMEM_SIZE(i), &mem, 1);
}
}
static void w5500_random_mac(uint8_t *mac_addr)
{
gen_random_mac(mac_addr, WIZNET_OUI_B0, WIZNET_OUI_B1, WIZNET_OUI_B2);
}
static int w5500_init(const struct device *dev)
{
int err;
uint8_t rtr[2];
const struct w5500_config *config = dev->config;
struct w5500_runtime *ctx = dev->data;
ctx->spi_cfg.operation = SPI_WORD_SET(8);
ctx->spi_cfg.frequency = config->spi_freq;
ctx->spi_cfg.slave = config->spi_slave;
ctx->spi = device_get_binding((char *)config->spi_port);
if (!ctx->spi) {
LOG_ERR("SPI master port %s not found", config->spi_port);
return -EINVAL;
}
#if DT_INST_SPI_DEV_HAS_CS_GPIOS(0)
ctx->spi_cs.gpio_dev = device_get_binding((char *)config->spi_cs_port);
if (!ctx->spi_cs.gpio_dev) {
LOG_ERR("SPI CS port %s not found", config->spi_cs_port);
return -EINVAL;
}
ctx->spi_cs.gpio_pin = config->spi_cs_pin;
ctx->spi_cs.gpio_dt_flags = config->spi_cs_dt_flags;
ctx->spi_cfg.cs = &ctx->spi_cs;
#endif
ctx->gpio = device_get_binding((char *)config->gpio_port);
if (!ctx->gpio) {
LOG_ERR("GPIO port %s not found", config->gpio_port);
return -EINVAL;
}
if (gpio_pin_configure(ctx->gpio, config->gpio_pin,
GPIO_INPUT | config->gpio_flags)) {
LOG_ERR("Unable to configure GPIO pin %u", config->gpio_pin);
return -EINVAL;
}
gpio_init_callback(&(ctx->gpio_cb), w5500_gpio_callback,
BIT(config->gpio_pin));
if (gpio_add_callback(ctx->gpio, &(ctx->gpio_cb))) {
return -EINVAL;
}
gpio_pin_interrupt_configure(ctx->gpio,
config->gpio_pin,
GPIO_INT_EDGE_FALLING);
ctx->reset = device_get_binding((char *)config->reset_port);
if (!ctx->reset) {
LOG_ERR("GPIO port %s not found", config->reset_port);
return -EINVAL;
}
if (gpio_pin_configure(ctx->reset, config->reset_pin,
GPIO_OUTPUT | config->reset_flags)) {
LOG_ERR("Unable to configure GPIO pin %u", config->reset_pin);
return -EINVAL;
}
gpio_pin_set(ctx->reset, DT_INST_GPIO_PIN(0, reset_gpios), 0);
k_usleep(500);
err = w5500_hw_reset(dev);
if (err) {
LOG_ERR("Reset failed");
return err;
}
w5500_set_macaddr(dev);
w5500_memory_configure(dev);
/* check retry time value */
w5500_spi_read(dev, W5500_RTR, rtr, 2);
if (sys_get_be16(rtr) != RTR_DEFAULT) {
LOG_ERR("Unable to read RTR register");
return -ENODEV;
}
k_thread_create(&ctx->thread, ctx->thread_stack,
CONFIG_ETH_W5500_RX_THREAD_STACK_SIZE,
(k_thread_entry_t)w5500_isr,
(void *)dev, NULL, NULL,
K_PRIO_COOP(CONFIG_ETH_W5500_RX_THREAD_PRIO),
0, K_NO_WAIT);
LOG_INF("W5500 Initialized");
return 0;
}
static struct w5500_runtime w5500_0_runtime = {
.generate_mac = w5500_random_mac,
.tx_sem = Z_SEM_INITIALIZER(w5500_0_runtime.tx_sem,
1, UINT_MAX),
.int_sem = Z_SEM_INITIALIZER(w5500_0_runtime.int_sem,
0, UINT_MAX),
};
static const struct w5500_config w5500_0_config = {
.gpio_port = DT_INST_GPIO_LABEL(0, int_gpios),
.gpio_pin = DT_INST_GPIO_PIN(0, int_gpios),
.gpio_flags = DT_INST_GPIO_FLAGS(0, int_gpios),
.reset_port = DT_INST_GPIO_LABEL(0, reset_gpios),
.reset_pin = DT_INST_GPIO_PIN(0, reset_gpios),
.reset_flags = DT_INST_GPIO_FLAGS(0, reset_gpios),
.spi_port = DT_INST_BUS_LABEL(0),
.spi_freq = DT_INST_PROP(0, spi_max_frequency),
.spi_slave = DT_INST_REG_ADDR(0),
#if DT_INST_SPI_DEV_HAS_CS_GPIOS(0)
.spi_cs_port = DT_INST_SPI_DEV_CS_GPIOS_LABEL(0),
.spi_cs_pin = DT_INST_SPI_DEV_CS_GPIOS_PIN(0),
.spi_cs_dt_flags = DT_INST_SPI_DEV_CS_GPIOS_FLAGS(0),
#endif
.timeout = CONFIG_ETH_W5500_TIMEOUT,
};
ETH_NET_DEVICE_INIT(eth_w5500, DT_INST_LABEL(0),
w5500_init, device_pm_control_nop,
&w5500_0_runtime, &w5500_0_config,
CONFIG_ETH_INIT_PRIORITY, &w5500_api_funcs, NET_ETH_MTU);

View file

@ -0,0 +1,113 @@
/* W5500 Stand-alone Ethernet Controller with SPI
*
* Copyright (c) 2020 Linumiz
* Author: Parthiban Nallathambi <parthiban@linumiz.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef _W5500_
#define _W5500_
/*
* W5500 common registers
*/
#define W5500_COMMON_REGS 0x0000
#define W5500_MR 0x0000 /* Mode Register */
#define W5500_GW 0x0001
#define MR_RST 0x80 /* S/W reset */
#define MR_PB 0x10 /* Ping block */
#define MR_AI 0x02 /* Address Auto-Increment */
#define MR_IND 0x01 /* Indirect mode */
#define W5500_SHAR 0x0009 /* Source MAC address */
#define W5500_IR 0x0015 /* Interrupt Register */
#define W5500_COMMON_REGS_LEN 0x0040
#define W5500_Sn_MR 0x0000 /* Sn Mode Register */
#define W5500_Sn_CR 0x0001 /* Sn Command Register */
#define W5500_Sn_IR 0x0002 /* Sn Interrupt Register */
#define W5500_Sn_SR 0x0003 /* Sn Status Register */
#define W5500_Sn_TX_FSR 0x0020 /* Sn Transmit free memory size */
#define W5500_Sn_TX_RD 0x0022 /* Sn Transmit memory read pointer */
#define W5500_Sn_TX_WR 0x0024 /* Sn Transmit memory write pointer */
#define W5500_Sn_RX_RSR 0x0026 /* Sn Receive free memory size */
#define W5500_Sn_RX_RD 0x0028 /* Sn Receive memory read pointer */
#define W5500_S0_REGS 0x10000
#define W5500_S0_MR (W5500_S0_REGS + W5500_Sn_MR)
#define S0_MR_MACRAW 0x04 /* MAC RAW mode */
#define S0_MR_MF 0x40 /* MAC Filter for W5500 */
#define W5500_S0_CR (W5500_S0_REGS + W5500_Sn_CR)
#define S0_CR_OPEN 0x01 /* OPEN command */
#define S0_CR_CLOSE 0x10 /* CLOSE command */
#define S0_CR_SEND 0x20 /* SEND command */
#define S0_CR_RECV 0x40 /* RECV command */
#define W5500_S0_IR (W5500_S0_REGS + W5500_Sn_IR)
#define S0_IR_SENDOK 0x10 /* complete sending */
#define S0_IR_RECV 0x04 /* receiving data */
#define W5500_S0_SR (W5500_S0_REGS + W5500_Sn_SR)
#define S0_SR_MACRAW 0x42 /* mac raw mode */
#define W5500_S0_TX_FSR (W5500_S0_REGS + W5500_Sn_TX_FSR)
#define W5500_S0_TX_RD (W5500_S0_REGS + W5500_Sn_TX_RD)
#define W5500_S0_TX_WR (W5500_S0_REGS + W5500_Sn_TX_WR)
#define W5500_S0_RX_RSR (W5500_S0_REGS + W5500_Sn_RX_RSR)
#define W5500_S0_RX_RD (W5500_S0_REGS + W5500_Sn_RX_RD)
#define W5500_S0_IMR (W5500_S0_REGS + W5500_Sn_IMR)
#define W5500_S0_MR_MF BIT(7) /* MAC Filter for W5500 */
#define W5500_Sn_REGS_LEN 0x0040
#define W5500_SIMR 0x0018 /* Socket Interrupt Mask Register */
#define IR_S0 0x01
#define RTR_DEFAULT 2000
#define W5500_RTR 0x0019 /* Retry Time-value Register */
#define W5500_Sn_RXMEM_SIZE(n) \
(0x1001e + (n) * 0x40000) /* Sn RX Memory Size */
#define W5500_Sn_TXMEM_SIZE(n) \
(0x1001f + (n) * 0x40000) /* Sn TX Memory Size */
#define W5500_Sn_TX_MEM_START 0x20000
#define W5500_TX_MEM_SIZE 0x04000
#define W5500_Sn_RX_MEM_START 0x30000
#define W5500_RX_MEM_SIZE 0x04000
struct w5500_config {
void (*config_func)(void);
const char *gpio_port;
uint8_t gpio_pin;
gpio_dt_flags_t gpio_flags;
const char *reset_port;
uint8_t reset_pin;
gpio_dt_flags_t reset_flags;
const char *spi_port;
gpio_pin_t spi_cs_pin;
gpio_dt_flags_t spi_cs_dt_flags;
const char *spi_cs_port;
uint32_t spi_freq;
uint8_t spi_slave;
uint8_t full_duplex;
int32_t timeout;
};
struct w5500_runtime {
struct net_if *iface;
K_THREAD_STACK_MEMBER(thread_stack,
CONFIG_ETH_W5500_RX_THREAD_STACK_SIZE);
struct k_thread thread;
uint8_t mac_addr[6];
const struct device *gpio;
const struct device *reset;
const struct device *spi;
struct spi_cs_control spi_cs;
struct spi_config spi_cfg;
struct gpio_callback gpio_cb;
struct k_sem tx_sem;
struct k_sem int_sem;
void (*generate_mac)(uint8_t *mac);
uint8_t buf[NET_ETH_MAX_FRAME_SIZE];
};
#endif /*_W5500_*/

View file

@ -0,0 +1,26 @@
# Copyright (c) 2020 Linumiz
# SPDX-License-Identifier: Apache-2.0
description: W5500 standalone 10/100BASE-T Ethernet controller with SPI interface
compatible: "wiznet,w5500"
include: [spi-device.yaml, ethernet.yaml]
properties:
int-gpios:
type: phandle-array
required: true
description: Interrupt pin.
The interrupt pin of W5500 is active low.
If connected directly the MCU pin should be configured
as active low.
reset-gpios:
type: phandle-array
required: true
description: Reset pin.
The reset pin of W5500 is active low.
If connected directly the MCU pin should be configured
as active low.

View file

@ -101,6 +101,7 @@
<&test_gpio 0 0>,
<&test_gpio 0 0>,
<&test_gpio 0 0>,
<&test_gpio 0 0>,
<&test_gpio 0 0>;
#include "spi.dtsi"

View file

@ -11,3 +11,5 @@ CONFIG_TEST_USERSPACE=y
CONFIG_SPI=y
CONFIG_ETH_ENC28J60=y
CONFIG_ETH_ENC28J60_0=y
CONFIG_ETH_W5500=y

View file

@ -542,3 +542,12 @@ test_spi_dac80508: dac80508@35 {
channel6-gain = <0>;
channel7-gain = <0>;
};
test_spi_w5500: w5500@36 {
compatible = "wiznet,w5500";
label = "w5500";
reg = <0x36>;
spi-max-frequency = <0>;
int-gpios = <&test_gpio 0 0>;
reset-gpios = <&test_gpio 0 0>;
};