From 8a97f2679b18799b6a9fab29b6fab741f8fc6d78 Mon Sep 17 00:00:00 2001 From: robert Date: Fri, 5 Apr 2024 11:23:23 -0400 Subject: [PATCH] XMC7 full working example --- examples/infineon/infineon-xmc7200/Makefile | 40 +++ examples/infineon/infineon-xmc7200/hal.c | 146 +++++++++++ examples/infineon/infineon-xmc7200/hal.h | 244 ++++++++++++++++++ examples/infineon/infineon-xmc7200/link.ld | 31 +++ examples/infineon/infineon-xmc7200/main.c | 32 +++ examples/infineon/infineon-xmc7200/mongoose.c | 1 + examples/infineon/infineon-xmc7200/mongoose.h | 1 + .../infineon-xmc7200/mongoose_config.h | 26 ++ examples/infineon/infineon-xmc7200/net.c | 1 + examples/infineon/infineon-xmc7200/net.h | 1 + .../infineon/infineon-xmc7200/packed_fs.c | 1 + examples/infineon/infineon-xmc7200/startup.c | 83 ++++++ .../infineon/infineon-xmc7200/system_cat1c.h | 1 + mongoose.c | 240 +++++++++++++++++ mongoose.h | 34 ++- src/drivers/phy.c | 18 ++ src/drivers/xmc7.c | 218 ++++++++++++++++ src/drivers/xmc7.h | 35 +++ src/net_builtin.h | 1 + 19 files changed, 1151 insertions(+), 3 deletions(-) create mode 100644 examples/infineon/infineon-xmc7200/Makefile create mode 100644 examples/infineon/infineon-xmc7200/hal.c create mode 100644 examples/infineon/infineon-xmc7200/hal.h create mode 100644 examples/infineon/infineon-xmc7200/link.ld create mode 100644 examples/infineon/infineon-xmc7200/main.c create mode 120000 examples/infineon/infineon-xmc7200/mongoose.c create mode 120000 examples/infineon/infineon-xmc7200/mongoose.h create mode 100644 examples/infineon/infineon-xmc7200/mongoose_config.h create mode 120000 examples/infineon/infineon-xmc7200/net.c create mode 120000 examples/infineon/infineon-xmc7200/net.h create mode 120000 examples/infineon/infineon-xmc7200/packed_fs.c create mode 100644 examples/infineon/infineon-xmc7200/startup.c create mode 100644 examples/infineon/infineon-xmc7200/system_cat1c.h create mode 100644 src/drivers/xmc7.c create mode 100644 src/drivers/xmc7.h diff --git a/examples/infineon/infineon-xmc7200/Makefile b/examples/infineon/infineon-xmc7200/Makefile new file mode 100644 index 0000000000..41541bceb1 --- /dev/null +++ b/examples/infineon/infineon-xmc7200/Makefile @@ -0,0 +1,40 @@ +CFLAGS = -W -Wall -Werror -Wextra -Wundef -Wshadow -Wdouble-promotion +CFLAGS += -Wformat-truncation -fno-common # -Wconversion is not SDK-friendly +CFLAGS += -g3 -Os -ffunction-sections -fdata-sections +CFLAGS += -I. -Icmsis_core/CMSIS/Core/Include -Icmsis_xmc7/devices/COMPONENT_CAT1C/include/ +CFLAGS += -Icmsis_xmc7/devices/COMPONENT_CAT1C/include/ip/ +CFLAGS += -mcpu=cortex-m7 -mthumb -mfloat-abi=hard -mfpu=fpv5-d16 $(CFLAGS_EXTRA) +LDSCRIPT = link.ld +LDFLAGS ?= -T$(LDSCRIPT) -nostdlib -nostartfiles --specs nano.specs -lc -lgcc -Wl,--gc-sections -Wl,-Map=$@.map + +SOURCES = main.c hal.c startup.c +CFLAGS += -D__ATOLLIC__ -D__STARTUP_CLEAR_BSS # Make startup code work as expected + +# Mongoose options are defined in mongoose_custom.h +SOURCES += mongoose.c net.c packed_fs.c + +# Example specific build options. See README.md +CFLAGS += -DHTTP_URL=\"http://0.0.0.0/\" -DHTTPS_URL=\"https://0.0.0.0/\" + +ifeq ($(OS),Windows_NT) + RM = cmd /C del /Q /F /S +else + RM = rm -rf +endif + +all build example: firmware.bin + +firmware.bin: firmware.elf + arm-none-eabi-objcopy -O binary $< $@ + +firmware.elf: cmsis_core cmsis_xmc7 $(SOURCES) hal.h link.ld Makefile + arm-none-eabi-gcc $(SOURCES) $(CFLAGS) $(LDFLAGS) -o $@ + arm-none-eabi-size $@ + +cmsis_core: # ARM CMSIS core headers + git clone -q --depth 1 -b 5.9.0 https://github.com/ARM-software/CMSIS_5 $@ +cmsis_xmc7: + git clone https://github.com/Infineon/mtb-pdl-cat1.git $@ + +clean: + $(RM) firmware.* *.su cmsis_core cmsis_xmc7 *.zip diff --git a/examples/infineon/infineon-xmc7200/hal.c b/examples/infineon/infineon-xmc7200/hal.c new file mode 100644 index 0000000000..d0240e6ad5 --- /dev/null +++ b/examples/infineon/infineon-xmc7200/hal.c @@ -0,0 +1,146 @@ +// Copyright (c) 2024 Cesanta Software Limited +// All rights reserved + +#include "hal.h" + +static volatile uint64_t s_ticks; // Milliseconds since boot +void SysTick_Handler(void) { // SyStick IRQ handler, triggered every 1ms + s_ticks++; +} + +void mg_random(void *buf, size_t len) { // Use on-board RNG + for (size_t n = 0; n < len; n += sizeof(uint32_t)) { + uint32_t r = rng_read(); + memcpy((char *) buf + n, &r, n + sizeof(r) > len ? len - n : sizeof(r)); + } +} + +uint64_t mg_millis(void) { // Let Mongoose use our uptime function + return s_ticks; // Return number of milliseconds since boot +} + +void hal_init(void) { + clock_init(); // Set system clock to SYS_FREQUENCY + SystemCoreClock = SYS_FREQUENCY; // Update SystemCoreClock global var + SysTick_Config(SystemCoreClock / 1000); // Sys tick every 1ms + rng_init(); // Initialise random number generator + + uart_init(UART_DEBUG, 115200); // Initialise UART + gpio_output(LED1); // Initialise LED1 + gpio_output(LED2); // Initialise LED2 + gpio_output(LED3); // Initialise LED3 + ethernet_init(); // Initialise Ethernet pins +} + +#if defined(__ARMCC_VERSION) +// Keil specific - implement IO printf redirection +int fputc(int c, FILE *stream) { + if (stream == stdout || stream == stderr) uart_write_byte(UART_DEBUG, c); + return c; +} +#elif defined(__GNUC__) +// ARM GCC specific. ARM GCC is shipped with Newlib C library. +// Implement newlib syscalls: +// _sbrk() for malloc +// _write() for printf redirection +// the rest are just stubs +#include // For _fstat() + +uint32_t SystemCoreClock; +void SystemInit(void) { // Called automatically by startup code +} + +int _fstat(int fd, struct stat *st) { + (void) fd, (void) st; + return -1; +} + +extern unsigned char _end[]; // End of data section, start of heap. See link.ld +static unsigned char *s_current_heap_end = _end; + +size_t hal_ram_used(void) { + return (size_t) (s_current_heap_end - _end); +} + +size_t hal_ram_free(void) { + unsigned char endofstack; + return (size_t) (&endofstack - s_current_heap_end); +} + +void *_sbrk(int incr) { + unsigned char *prev_heap; + unsigned char *heap_end = (unsigned char *) ((size_t) &heap_end - 256); + prev_heap = s_current_heap_end; + // Check how much space we got from the heap end to the stack end + if (s_current_heap_end + incr > heap_end) return (void *) -1; + s_current_heap_end += incr; + return prev_heap; +} + +int _open(const char *path) { + (void) path; + return -1; +} + +int _close(int fd) { + (void) fd; + return -1; +} + +int _isatty(int fd) { + (void) fd; + return 1; +} + +int _lseek(int fd, int ptr, int dir) { + (void) fd, (void) ptr, (void) dir; + return 0; +} + +void _exit(int status) { + (void) status; + for (;;) asm volatile("BKPT #0"); +} + +void _kill(int pid, int sig) { + (void) pid, (void) sig; +} + +int _getpid(void) { + return -1; +} + +int _write(int fd, char *ptr, int len) { + (void) fd, (void) ptr, (void) len; + if (fd == 1) uart_write_buf(UART_DEBUG, ptr, (size_t) len); + return -1; +} + +int _read(int fd, char *ptr, int len) { + (void) fd, (void) ptr, (void) len; + return -1; +} + +int _link(const char *a, const char *b) { + (void) a, (void) b; + return -1; +} + +int _unlink(const char *a) { + (void) a; + return -1; +} + +int _stat(const char *path, struct stat *st) { + (void) path, (void) st; + return -1; +} + +int mkdir(const char *path, mode_t mode) { + (void) path, (void) mode; + return -1; +} + +void _init(void) { +} +#endif // __GNUC__ diff --git a/examples/infineon/infineon-xmc7200/hal.h b/examples/infineon/infineon-xmc7200/hal.h new file mode 100644 index 0000000000..90428033fa --- /dev/null +++ b/examples/infineon/infineon-xmc7200/hal.h @@ -0,0 +1,244 @@ +// Copyright (c) 2023 Cesanta Software Limited +// All rights reserved + +#pragma once + +#include +#include +#include +#include + +#define LED1 PIN(16, 1) +#define LED2 PIN(16, 2) +#define LED3 PIN(16, 3) + +#include "xmc7200d_e272k8384.h" + +#define BIT(x) (1UL << (x)) +#define CLRSET(reg, clear, set) ((reg) = ((reg) & ~(clear)) | (set)) +#define PIN(bank, num) ((bank << 8) | (num)) +#define PINNO(pin) (pin & 255) +#define PINBANK(pin) (pin >> 8) + +void hal_init(void); +size_t hal_ram_free(void); +size_t hal_ram_used(void); + +static inline void spin(volatile uint32_t count) { + while (count--) (void) 0; +} + +extern uint32_t SystemCoreClock; + +enum {PLL_FEEDBACK = 50, PLL_REF = 1, PLL_OUT = 4}; +#define CLK_IMO 8000000UL +#define SYS_FREQUENCY ((CLK_IMO * PLL_FEEDBACK) / (PLL_REF * PLL_OUT)) + +#ifndef UART_DEBUG +#define UART_DEBUG SCB3 +#endif + +enum { GPIO_MODE_INPUT, GPIO_MODE_OUTPUT, GPIO_MODE_AF, GPIO_MODE_ANALOG }; +enum { GPIO_HIGHZ = 0, GPIO_PULLUP = 2, GPIO_PULLDOWN = 3, GPIO_OPENDRAIN_LOW = 4, + GPIO_OPENDRAIN_HIGH = 5, GPIO_STRONG = 6, GPIO_PULLUP_DOWN = 7}; +enum { GPIO_SPEED_LOW = 3, GPIO_SPEED_MEDIUM = 2, GPIO_SPEED_HIGH = 0}; +#undef GPIO +#define GPIO_TypeDef GPIO_PRT_Type +#define GPIO(N) ((GPIO_TypeDef *) (GPIO_BASE + 0x80 * (N))) + +static GPIO_TypeDef *gpio_bank(uint16_t pin) { return GPIO(PINBANK(pin)); } + +static inline void gpio_init(uint16_t pin, uint8_t mode, uint8_t type, + uint8_t speed, uint8_t pull, uint8_t af) { + (void) pin, (void) mode, (void) type, (void) speed, (void) pull, (void) af; + GPIO_TypeDef *gpio = gpio_bank(pin); + uint8_t pinno = PINNO(pin); + uint32_t msk, pos; + + // configure input / output direction + if (mode == GPIO_MODE_INPUT) { + gpio->CFG |= 1 << (4 * pinno + 3); // enable input buffer (IN_ENx) + } + + if (af || (mode == GPIO_MODE_AF && af)) { + // configure alternate function + HSIOM_PRT_Type* hsiom = ((HSIOM_PRT_Type*) HSIOM) + PINBANK(pin); + volatile uint32_t *port_sel = pinno < 4 ? &hsiom->PORT_SEL0 : &hsiom->PORT_SEL1; + pos = 8 * (pinno % 4), msk = 0x1f << pos; + *port_sel &= ~msk, *port_sel |= af << pos; + } + + // configure driver mode + msk = 7, pos = 4 * pinno; + CLRSET(gpio->CFG, msk << pos, type << pos); + + // configure speed + msk = 3, pos = 2 * pinno + 16; + CLRSET(gpio->CFG_OUT, msk << pos, speed << pos); + + if (mode == GPIO_MODE_OUTPUT /*&& af == 0*/) { + gpio->OUT_SET = (1 << pinno); + } +} + +static inline void gpio_input(uint16_t pin) { + gpio_init(pin, GPIO_MODE_INPUT, GPIO_HIGHZ, GPIO_SPEED_HIGH, + 0, 0); +} + +static inline void gpio_output(uint16_t pin) { + gpio_init(pin, GPIO_MODE_OUTPUT, GPIO_STRONG, GPIO_SPEED_MEDIUM, + 0, 0); +} + +static inline bool gpio_read(uint16_t pin) { + GPIO_TypeDef *gpio = gpio_bank(pin); + uint8_t pinno = PINNO(pin); + if (gpio->CFG & (1 << (4 * pinno + 3))) { + // pin mode is input, reading from GPIO_PRT_IN + return gpio->IN & (1 << pinno); + } else { + // pin mode is output, reading from GPIO_PRT_OUT + return gpio->OUT & (1 << pinno); + } +} + +static inline void gpio_write(uint16_t pin, bool value) { + GPIO_TypeDef *gpio = gpio_bank(pin); + uint8_t pinno = PINNO(pin); + if (value) { + gpio->OUT_SET = 1 << pinno; + } else { + gpio->OUT_CLR = 1 << pinno; + } +} + +static inline void gpio_toggle(uint16_t pin) { + gpio_write(pin, !gpio_read(pin)); +} + +static inline void uart_init(volatile CySCB_Type *uart, unsigned long baud) { + (void) uart, (void) baud; + uint16_t rx = 0, tx = 0; + if (uart == SCB3) { + rx = PIN(13, 0), tx = PIN(13, 1); + } else { + return; // unsupported uart + } + + // set pins + gpio_init(rx, GPIO_MODE_INPUT, GPIO_HIGHZ, GPIO_SPEED_HIGH, 0, 17); + gpio_init(tx, GPIO_MODE_OUTPUT, GPIO_STRONG, GPIO_SPEED_HIGH, 0, 17); + + // enable peripheral clock (18.6.2) + // compute divider first (we choose 24 bit divider 0) + unsigned long div = 0, frac = 0, ovs = 16; + div = SYS_FREQUENCY / (baud * ovs); + if (div == 0) div = 1; + frac = SYS_FREQUENCY % (baud * ovs); + frac = (frac * 100) / (baud * ovs); + PERI_PCLK->GR[1].DIV_CMD = (3 << PERI_PCLK_GR_DIV_CMD_TYPE_SEL_Pos) | + PERI_PCLK_GR_DIV_CMD_PA_DIV_SEL_Msk | + PERI_PCLK_GR_DIV_CMD_PA_TYPE_SEL_Msk; + PERI_PCLK->GR[1].DIV_CMD |= PERI_PCLK_GR_DIV_CMD_DISABLE_Msk; // disable divider + PERI_PCLK->GR[1].DIV_24_5_CTL[0] = (((uint8_t) (div - 1)) << PERI_PCLK_GR_DIV_24_5_CTL_INT24_DIV_Pos) | + (frac << PERI_PCLK_GR_DIV_24_5_CTL_FRAC5_DIV_Pos); + PERI_PCLK->GR[1].DIV_CMD = (3 << PERI_PCLK_GR_DIV_CMD_TYPE_SEL_Pos) | + PERI_PCLK_GR_DIV_CMD_PA_DIV_SEL_Msk | + PERI_PCLK_GR_DIV_CMD_PA_TYPE_SEL_Msk;; + PERI_PCLK->GR[1].DIV_CMD |= PERI_PCLK_GR_DIV_CMD_ENABLE_Msk; // enable divider + PERI_PCLK->GR[1].CLOCK_CTL[PCLK_SCB3_CLOCK & 0xff] = 3 << PERI_PCLK_GR_CLOCK_CTL_TYPE_SEL_Pos; // connect SCB3 to div_24_5_ctl[0] + + // configure UART interface + uart->CTRL = ((ovs - 1) << SCB_CTRL_OVS_Pos) | (2 << SCB_CTRL_MODE_Pos); + uart->UART_CTRL = 0; + uart->UART_RX_CTRL = 1 << SCB_UART_RX_CTRL_STOP_BITS_Pos; + uart->RX_CTRL = 7 << SCB_RX_CTRL_DATA_WIDTH_Pos; + uart->UART_TX_CTRL = 1 << SCB_UART_TX_CTRL_STOP_BITS_Pos; + uart->TX_CTRL = 7 << SCB_TX_CTRL_DATA_WIDTH_Pos; + uart->TX_FIFO_CTRL = 1 << 16; + uart->TX_FIFO_CTRL = 0; + uart->CTRL |= 1 << SCB_CTRL_ENABLED_Pos; +} + +static inline void uart_write_byte(volatile CySCB_Type *uart, uint8_t byte) { + (void) byte; (void) uart; + while((uart->INTR_TX & SCB_INTR_TX_EMPTY_Msk) == 0) spin(1); + uart->TX_FIFO_WR = byte; + uart->INTR_TX |= ~SCB_INTR_TX_EMPTY_Msk; +} + +static inline void uart_write_buf(volatile CySCB_Type *uart, char *buf, size_t len) { + while (len-- > 0) uart_write_byte(uart, *(uint8_t *) buf++); +} + +static inline void rng_init(void) { +} +static inline uint32_t rng_read(void) { + return 0; +} + +static inline void ethernet_init(void) { + gpio_init(PIN(26, 0), GPIO_MODE_INPUT, GPIO_HIGHZ, GPIO_SPEED_HIGH, 0, 27); // ETH1_REF_CLK + gpio_init(PIN(26, 1), GPIO_MODE_OUTPUT, GPIO_STRONG, GPIO_SPEED_HIGH, 0, 27); // ETH1_TX_CTL + gpio_init(PIN(26, 2), GPIO_MODE_OUTPUT, GPIO_STRONG, GPIO_SPEED_HIGH, 0, 27); // ETH1_TX_CLK + gpio_init(PIN(26, 3), GPIO_MODE_OUTPUT, GPIO_STRONG, GPIO_SPEED_HIGH, 0, 27); // ETH1_TXD_0 + gpio_init(PIN(26, 4), GPIO_MODE_OUTPUT, GPIO_STRONG, GPIO_SPEED_HIGH, 0, 27); // ETH1_TXD_1 + gpio_init(PIN(26, 5), GPIO_MODE_OUTPUT, GPIO_STRONG, GPIO_SPEED_HIGH, 0, 27); // ETH1_TXD_2 + gpio_init(PIN(26, 6), GPIO_MODE_OUTPUT, GPIO_STRONG, GPIO_SPEED_HIGH, 0, 27); // ETH1_TXD_3 + gpio_init(PIN(26, 7), GPIO_MODE_INPUT, GPIO_HIGHZ, GPIO_SPEED_HIGH, 0, 27); // ETH1_RXD_0 + + gpio_init(PIN(27, 0), GPIO_MODE_INPUT, GPIO_HIGHZ, GPIO_SPEED_HIGH, 0, 27); // ETH1_RXD_1 + gpio_init(PIN(27, 1), GPIO_MODE_INPUT, GPIO_HIGHZ, GPIO_SPEED_HIGH, 0, 27); // ETH1_RXD_2 + gpio_init(PIN(27, 2), GPIO_MODE_INPUT, GPIO_HIGHZ, GPIO_SPEED_HIGH, 0, 27); // ETH1_RXD_3 + gpio_init(PIN(27, 3), GPIO_MODE_INPUT, GPIO_HIGHZ, GPIO_SPEED_HIGH, 0, 27); // ETH1_RX_CTL + gpio_init(PIN(27, 4), GPIO_MODE_INPUT, GPIO_HIGHZ, GPIO_SPEED_HIGH, 0, 27); // ETH1_RX_CLK + gpio_init(PIN(27, 5), GPIO_MODE_INPUT, GPIO_STRONG, GPIO_SPEED_LOW, 0, 27); // ETH1_MDIO + gpio_init(PIN(27, 6), GPIO_MODE_OUTPUT, GPIO_STRONG, GPIO_SPEED_LOW, 0, 27); // ETH1_MDC + //gpio_init(PIN(27, 7), GPIO_MODE_OUTPUT, GPIO_HIGHZ, GPIO_SPEED_HIGH, 0, 0); // ETH1_RST + + CPUSS->CM7_0_SYSTEM_INT_CTL[eth_1_interrupt_eth_0_IRQn] = 0x80000003; // assign CPU interrupt #3 + NVIC->ISER[0] = 1 << 3; + + spin(10000000); // artificial delay to wait for PHY init +} + +static inline void clock_init(void) { + SCB->CPACR |= ((3UL << 10 * 2) | (3UL << 11 * 2)); // Enable FPU + asm("DSB"); + asm("ISB"); + + // configure PLL + CLRSET(SRSS->CLK_PLL400M[0].CONFIG, CLK_PLL400M_CONFIG_BYPASS_SEL_Msk, BIT(29)); // First bypass PLL + spin(10); + SRSS->CLK_PLL400M[0].CONFIG &= ~CLK_PLL400M_CONFIG_ENABLE_Msk; // disable the PLL itself + + // IMO source generates a frequency of 8MHz. The final frequency will be + // calculated as (CLK_IMO * feedback) / (reference * output_div) + CLRSET(SRSS->CLK_PLL400M[0].CONFIG, CLK_PLL400M_CONFIG_FEEDBACK_DIV_Msk, PLL_FEEDBACK << CLK_PLL400M_CONFIG_FEEDBACK_DIV_Pos); + CLRSET(SRSS->CLK_PLL400M[0].CONFIG, CLK_PLL400M_CONFIG_REFERENCE_DIV_Msk, PLL_REF << CLK_PLL400M_CONFIG_REFERENCE_DIV_Pos); + CLRSET(SRSS->CLK_PLL400M[0].CONFIG, CLK_PLL400M_CONFIG_OUTPUT_DIV_Msk, PLL_OUT << CLK_PLL400M_CONFIG_OUTPUT_DIV_Pos); + CLRSET(SRSS->CLK_PLL400M[0].CONFIG2, CLK_PLL400M_CONFIG2_FRAC_DIV_Msk, 0); + CLRSET(SRSS->CLK_PLL400M[0].CONFIG2, CLK_PLL400M_CONFIG2_FRAC_DITHER_EN_Msk, 0); + CLRSET(SRSS->CLK_PLL400M[0].CONFIG2, CLK_PLL400M_CONFIG2_FRAC_EN_Msk, 1 << CLK_PLL400M_CONFIG2_FRAC_EN_Pos); + CLRSET(SRSS->CLK_PLL400M[0].CONFIG, CLK_PLL400M_CONFIG_BYPASS_SEL_Msk, 0); + spin(10); + SRSS->CLK_PLL400M[0].CONFIG |= CLK_PLL400M_CONFIG_ENABLE_Msk; // enable the PLL + while (SRSS->CLK_PLL400M[0].CONFIG & 1) spin(1); + + // configure PATH1 with source set to IMO + SRSS->CLK_PATH_SELECT[1] = 0; + + // enable CLK_HFx + uint8_t clocks[] = {0, 1, 2, 3, 4, 5, 6}; + for (size_t i = 0; i < sizeof(clocks) / sizeof(uint8_t); i++) { + CLRSET(SRSS->CLK_ROOT_SELECT[clocks[i]], SRSS_CLK_ROOT_SELECT_ROOT_MUX_Msk, 1); // choose PATH1 + CLRSET(SRSS->CLK_ROOT_SELECT[clocks[i]], SRSS_CLK_ROOT_SELECT_DIRECT_MUX_Msk, 1 << SRSS_CLK_ROOT_SELECT_DIRECT_MUX_Pos); + if (clocks[i] != 0) // CLF_HF0 is already enabled + SRSS->CLK_ROOT_SELECT[clocks[i]] |= SRSS_CLK_ROOT_SELECT_ENABLE_Msk; // enable clock root + } + + // set systick frequency + uint32_t tenms = SYS_FREQUENCY / 100 - 1; // number of cycles executed in 10ms + CPUSS->SYSTICK_CTL = tenms | (3 << CPUSS_SYSTICK_CTL_CLOCK_SOURCE_Pos); // select CLK_HF as source +} diff --git a/examples/infineon/infineon-xmc7200/link.ld b/examples/infineon/infineon-xmc7200/link.ld new file mode 100644 index 0000000000..502ae61ae3 --- /dev/null +++ b/examples/infineon/infineon-xmc7200/link.ld @@ -0,0 +1,31 @@ +OUTPUT_FORMAT("elf32-littlearm") +OUTPUT_ARCH(arm) +ENTRY(Reset_Handler) + +MEMORY +{ + flash(RX) : ORIGIN = 0x10080000, LENGTH = 0x80000 + sram(!RX) : ORIGIN = 0x28000800, LENGTH = 510K +} + +_estack = ORIGIN(sram) + LENGTH(sram); + +SECTIONS +{ + .vectors : { . = ALIGN(4); KEEP(*(.vectors)); . = ALIGN(4); } > flash + .text : { *(.text*) } > flash + .rodata : { *(.rodata*) } > flash + + .data : { + _sdata = .; + *(.first_data) + *(.data SORT(.data.*)) + _edata = .; + } > sram AT > flash + _sidata = LOADADDR(.data); + + .bss : { _sbss = .; *(.bss SORT(.bss.*) COMMON) _ebss = .; } > sram + + . = ALIGN(8); + _end = .; +} diff --git a/examples/infineon/infineon-xmc7200/main.c b/examples/infineon/infineon-xmc7200/main.c new file mode 100644 index 0000000000..0c3d910c64 --- /dev/null +++ b/examples/infineon/infineon-xmc7200/main.c @@ -0,0 +1,32 @@ +// Copyright (c) 2024 Cesanta Software Limited +// All rights reserved + +#include "hal.h" +#include "mongoose.h" +#include "net.h" + +#define BLINK_PERIOD_MS 1000 + +static void timer_fn(void *arg) { + gpio_toggle(LED1); // Blink LED + (void) arg; // Unused +} + +int main(void) { + struct mg_mgr mgr; // Mongoose event manager + + hal_init(); // Cross-platform hardware init + + mg_mgr_init(&mgr); // Initialise it + mg_log_set(MG_LL_DEBUG); // Set log level to debug + mg_timer_add(&mgr, BLINK_PERIOD_MS, MG_TIMER_REPEAT, timer_fn, &mgr); + + MG_INFO(("Initialising application...")); + web_init(&mgr); + + for (;;) { + mg_mgr_poll(&mgr, 0); + } + + return 0; +} diff --git a/examples/infineon/infineon-xmc7200/mongoose.c b/examples/infineon/infineon-xmc7200/mongoose.c new file mode 120000 index 0000000000..5ff013f2b0 --- /dev/null +++ b/examples/infineon/infineon-xmc7200/mongoose.c @@ -0,0 +1 @@ +/home/ubuntu/git/mongoose/mongoose.c \ No newline at end of file diff --git a/examples/infineon/infineon-xmc7200/mongoose.h b/examples/infineon/infineon-xmc7200/mongoose.h new file mode 120000 index 0000000000..d96410f91c --- /dev/null +++ b/examples/infineon/infineon-xmc7200/mongoose.h @@ -0,0 +1 @@ +/home/ubuntu/git/mongoose/mongoose.h \ No newline at end of file diff --git a/examples/infineon/infineon-xmc7200/mongoose_config.h b/examples/infineon/infineon-xmc7200/mongoose_config.h new file mode 100644 index 0000000000..39a2a22010 --- /dev/null +++ b/examples/infineon/infineon-xmc7200/mongoose_config.h @@ -0,0 +1,26 @@ +#pragma once + +// See https://mongoose.ws/documentation/#build-options +#define MG_ARCH MG_ARCH_NEWLIB + +#define MG_ENABLE_TCPIP 1 +#define MG_ENABLE_DRIVER_XMC7 1 +#define MG_IO_SIZE 256 +#define MG_ENABLE_CUSTOM_MILLIS 1 +#define MG_ENABLE_CUSTOM_RANDOM 1 +#define MG_ENABLE_PACKED_FS 1 + +// For static IP configuration, define MG_TCPIP_{IP,MASK,GW} +// By default, those are set to zero, meaning that DHCP is used +// +// #define MG_TCPIP_IP MG_IPV4(192, 168, 1, 10) +// #define MG_TCPIP_GW MG_IPV4(192, 168, 1, 1) +// #define MG_TCPIP_MASK MG_IPV4(255, 255, 255, 0) + +// Set custom MAC address. By default, it is randomly generated +// Using a build-time constant: +// #define MG_SET_MAC_ADDRESS(mac) do { uint8_t buf_[6] = {2,3,4,5,6,7}; memmove(mac, buf_, sizeof(buf_)); } while (0) +// +// Using custom function: +// extern void my_function(unsigned char *mac); +// #define MG_SET_MAC_ADDRESS(mac) my_function(mac) diff --git a/examples/infineon/infineon-xmc7200/net.c b/examples/infineon/infineon-xmc7200/net.c new file mode 120000 index 0000000000..fe0e6f06e7 --- /dev/null +++ b/examples/infineon/infineon-xmc7200/net.c @@ -0,0 +1 @@ +../../device-dashboard/net.c \ No newline at end of file diff --git a/examples/infineon/infineon-xmc7200/net.h b/examples/infineon/infineon-xmc7200/net.h new file mode 120000 index 0000000000..9de896ef4e --- /dev/null +++ b/examples/infineon/infineon-xmc7200/net.h @@ -0,0 +1 @@ +../../device-dashboard/net.h \ No newline at end of file diff --git a/examples/infineon/infineon-xmc7200/packed_fs.c b/examples/infineon/infineon-xmc7200/packed_fs.c new file mode 120000 index 0000000000..e06bf09258 --- /dev/null +++ b/examples/infineon/infineon-xmc7200/packed_fs.c @@ -0,0 +1 @@ +../../device-dashboard/packed_fs.c \ No newline at end of file diff --git a/examples/infineon/infineon-xmc7200/startup.c b/examples/infineon/infineon-xmc7200/startup.c new file mode 100644 index 0000000000..06643a30cc --- /dev/null +++ b/examples/infineon/infineon-xmc7200/startup.c @@ -0,0 +1,83 @@ +#include "xmc7200d_e272k8384.h" + +void Reset_Handler(void); // Defined below +void Dummy_Handler(void); // Defined below +void SysTick_Handler(void); // Defined in main.c +void SystemInit(void); // Defined in main.c, called by reset handler +void _estack(void); // Defined in link.ld + +#define WEAK_ALIAS __attribute__((weak, alias("Default_Handler"))) + +WEAK_ALIAS void NMI_Handler(void); +WEAK_ALIAS void HardFault_Handler(void); +WEAK_ALIAS void SVCall_Handler(void); +WEAK_ALIAS void PendSV_Handler(void); +WEAK_ALIAS void SysTick_Handler(void); + +WEAK_ALIAS void Default_Intr_Handler(void); +WEAK_ALIAS void CM0P_CpuIntr0_Handler(void); +WEAK_ALIAS void CM0P_CpuIntr1_Handler(void); +WEAK_ALIAS void CM0P_CpuIntr2_Handler(void); +WEAK_ALIAS void CM0P_CpuIntr4_Handler(void); +WEAK_ALIAS void CM0P_CpuIntr5_Handler(void); +WEAK_ALIAS void CM0P_CpuIntr6_Handler(void); +WEAK_ALIAS void CM0P_CpuIntr7_Handler(void); +WEAK_ALIAS void ETH0_IRQHandler(void); + +void CM0P_CpuIntr3_Handler(void) { + ETH0_IRQHandler(); +} + +__attribute__((section(".vectors"))) void (*const tab[16 + 16])(void) = { + _estack, + Reset_Handler, + NMI_Handler, + HardFault_Handler, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + SVCall_Handler, + 0, + 0, + PendSV_Handler, + SysTick_Handler, + CM0P_CpuIntr0_Handler, + CM0P_CpuIntr1_Handler, + CM0P_CpuIntr2_Handler, + CM0P_CpuIntr3_Handler, + CM0P_CpuIntr4_Handler, + CM0P_CpuIntr5_Handler, + CM0P_CpuIntr6_Handler, + CM0P_CpuIntr7_Handler, + Default_Intr_Handler, + Default_Intr_Handler, + Default_Intr_Handler, + Default_Intr_Handler, + Default_Intr_Handler, + Default_Intr_Handler, + Default_Intr_Handler, + Default_Intr_Handler +}; + +__attribute__((naked, noreturn)) void Reset_Handler(void) { + // Clear BSS section, and copy data section from flash to RAM + extern long _sbss, _ebss, _sdata, _edata, _sidata; + for (long *src = &_sbss; src < &_ebss; src++) *src = 0; + for (long *src = &_sdata, *dst = &_sidata; src < &_edata;) *src++ = *dst++; + + SCB->VTOR = (uint32_t) &tab; + SystemInit(); + + // Call main() + extern void main(void); + main(); + for (;;) (void) 0; // Infinite loop +} + +void Default_Handler(void) { + for (;;) (void) 0; +} diff --git a/examples/infineon/infineon-xmc7200/system_cat1c.h b/examples/infineon/infineon-xmc7200/system_cat1c.h new file mode 100644 index 0000000000..999e976841 --- /dev/null +++ b/examples/infineon/infineon-xmc7200/system_cat1c.h @@ -0,0 +1 @@ +// The cmsis header file for XMC7200 includes a file with this name, which is inexistent in the cmsis_xmc7 directory. This is the reason this file was created. Workaround needed. diff --git a/mongoose.c b/mongoose.c index 1e137524be..d86480d243 100644 --- a/mongoose.c +++ b/mongoose.c @@ -15611,6 +15611,20 @@ static const char *mg_phy_id_to_str(uint16_t id1, uint16_t id2) { (void) id2; } +static void mg_phy_set_clk_out(struct mg_phy *phy, uint8_t phy_addr) { + uint16_t id1, id2; + id1 = phy->read_reg(phy_addr, MG_PHY_REG_ID1); + id2 = phy->read_reg(phy_addr, MG_PHY_REG_ID2); + + if (id1 == MG_PHY_DP83x && id2 == MG_PHY_DP83867) { + // write 0x10d to IO_MUX_CFG (0x0170) + phy->write_reg(phy_addr, 0x0d, 0x1f); + phy->write_reg(phy_addr, 0x0e, 0x170); + phy->write_reg(phy_addr, 0x0d, 0x401f); + phy->write_reg(phy_addr, 0x0e, 0x10d); + } +} + void mg_phy_init(struct mg_phy *phy, uint8_t phy_addr, uint8_t config) { uint16_t id1, id2; phy->write_reg(phy_addr, MG_PHY_REG_BCR, MG_BIT(15)); // Reset PHY @@ -15620,6 +15634,10 @@ void mg_phy_init(struct mg_phy *phy, uint8_t phy_addr, uint8_t config) { id2 = phy->read_reg(phy_addr, MG_PHY_REG_ID2); MG_INFO(("PHY ID: %#04x %#04x (%s)", id1, id2, mg_phy_id_to_str(id1, id2))); + if (id1 == MG_PHY_DP83x && id2 == MG_PHY_DP83867) { + mg_phy_set_clk_out(phy, phy_addr); + } + if (config & MG_PHY_CLOCKS_MAC) { // Use PHY crystal oscillator (preserve defaults) // nothing to do @@ -17031,3 +17049,225 @@ static bool w5500_up(struct mg_tcpip_if *ifp) { struct mg_tcpip_driver mg_tcpip_driver_w5500 = {w5500_init, w5500_tx, w5500_rx, w5500_up}; #endif + +#ifdef MG_ENABLE_LINES +#line 1 "src/drivers/xmc7.c" +#endif + + +#if MG_ENABLE_TCPIP && defined(MG_ENABLE_DRIVER_XMC7) && MG_ENABLE_DRIVER_XMC7 + +struct ETH_Type { + volatile uint32_t CTL, STATUS, RESERVED[1022], NETWORK_CONTROL, + NETWORK_CONFIG, NETWORK_STATUS, USER_IO_REGISTER, DMA_CONFIG, + TRANSMIT_STATUS, RECEIVE_Q_PTR, TRANSMIT_Q_PTR, RECEIVE_STATUS, + INT_STATUS, INT_ENABLE, INT_DISABLE, INT_MASK, PHY_MANAGEMENT, PAUSE_TIME, + TX_PAUSE_QUANTUM, PBUF_TXCUTTHRU, PBUF_RXCUTTHRU, JUMBO_MAX_LENGTH, + EXTERNAL_FIFO_INTERFACE, RESERVED1, AXI_MAX_PIPELINE, RSC_CONTROL, + INT_MODERATION, SYS_WAKE_TIME, RESERVED2[7], HASH_BOTTOM, HASH_TOP, + SPEC_ADD1_BOTTOM, SPEC_ADD1_TOP, SPEC_ADD2_BOTTOM, SPEC_ADD2_TOP, + SPEC_ADD3_BOTTOM, SPEC_ADD3_TOP, SPEC_ADD4_BOTTOM, SPEC_ADD4_TOP, + SPEC_TYPE1, SPEC_TYPE2, SPEC_TYPE3, SPEC_TYPE4, WOL_REGISTER, + STRETCH_RATIO, STACKED_VLAN, TX_PFC_PAUSE, MASK_ADD1_BOTTOM, + MASK_ADD1_TOP, DMA_ADDR_OR_MASK, RX_PTP_UNICAST, TX_PTP_UNICAST, + TSU_NSEC_CMP, TSU_SEC_CMP, TSU_MSB_SEC_CMP, TSU_PTP_TX_MSB_SEC, + TSU_PTP_RX_MSB_SEC, TSU_PEER_TX_MSB_SEC, TSU_PEER_RX_MSB_SEC, + DPRAM_FILL_DBG, REVISION_REG, OCTETS_TXED_BOTTOM, OCTETS_TXED_TOP, + FRAMES_TXED_OK, BROADCAST_TXED, MULTICAST_TXED, PAUSE_FRAMES_TXED, + FRAMES_TXED_64, FRAMES_TXED_65, FRAMES_TXED_128, FRAMES_TXED_256, + FRAMES_TXED_512, FRAMES_TXED_1024, FRAMES_TXED_1519, TX_UNDERRUNS, + SINGLE_COLLISIONS, MULTIPLE_COLLISIONS, EXCESSIVE_COLLISIONS, + LATE_COLLISIONS, DEFERRED_FRAMES, CRS_ERRORS, OCTETS_RXED_BOTTOM, + OCTETS_RXED_TOP, FRAMES_RXED_OK, BROADCAST_RXED, MULTICAST_RXED, + PAUSE_FRAMES_RXED, FRAMES_RXED_64, FRAMES_RXED_65, FRAMES_RXED_128, + FRAMES_RXED_256, FRAMES_RXED_512, FRAMES_RXED_1024, FRAMES_RXED_1519, + UNDERSIZE_FRAMES, EXCESSIVE_RX_LENGTH, RX_JABBERS, FCS_ERRORS, + RX_LENGTH_ERRORS, RX_SYMBOL_ERRORS, ALIGNMENT_ERRORS, RX_RESOURCE_ERRORS, + RX_OVERRUNS, RX_IP_CK_ERRORS, RX_TCP_CK_ERRORS, RX_UDP_CK_ERRORS, + AUTO_FLUSHED_PKTS, RESERVED3, TSU_TIMER_INCR_SUB_NSEC, TSU_TIMER_MSB_SEC, + TSU_STROBE_MSB_SEC, TSU_STROBE_SEC, TSU_STROBE_NSEC, TSU_TIMER_SEC, + TSU_TIMER_NSEC, TSU_TIMER_ADJUST, TSU_TIMER_INCR, TSU_PTP_TX_SEC, + TSU_PTP_TX_NSEC, TSU_PTP_RX_SEC, TSU_PTP_RX_NSEC, TSU_PEER_TX_SEC, + TSU_PEER_TX_NSEC, TSU_PEER_RX_SEC, TSU_PEER_RX_NSEC, PCS_CONTROL, + PCS_STATUS, RESERVED4[2], PCS_AN_ADV, PCS_AN_LP_BASE, PCS_AN_EXP, + PCS_AN_NP_TX, PCS_AN_LP_NP, RESERVED5[6], PCS_AN_EXT_STATUS, RESERVED6[8], + TX_PAUSE_QUANTUM1, TX_PAUSE_QUANTUM2, TX_PAUSE_QUANTUM3, RESERVED7, + RX_LPI, RX_LPI_TIME, TX_LPI, TX_LPI_TIME, DESIGNCFG_DEBUG1, + DESIGNCFG_DEBUG2, DESIGNCFG_DEBUG3, DESIGNCFG_DEBUG4, DESIGNCFG_DEBUG5, + DESIGNCFG_DEBUG6, DESIGNCFG_DEBUG7, DESIGNCFG_DEBUG8, DESIGNCFG_DEBUG9, + DESIGNCFG_DEBUG10, RESERVED8[22], SPEC_ADD5_BOTTOM, SPEC_ADD5_TOP, + RESERVED9[60], SPEC_ADD36_BOTTOM, SPEC_ADD36_TOP, INT_Q1_STATUS, + INT_Q2_STATUS, INT_Q3_STATUS, RESERVED10[11], INT_Q15_STATUS, RESERVED11, + TRANSMIT_Q1_PTR, TRANSMIT_Q2_PTR, TRANSMIT_Q3_PTR, RESERVED12[11], + TRANSMIT_Q15_PTR, RESERVED13, RECEIVE_Q1_PTR, RECEIVE_Q2_PTR, + RECEIVE_Q3_PTR, RESERVED14[3], RECEIVE_Q7_PTR, RESERVED15, + DMA_RXBUF_SIZE_Q1, DMA_RXBUF_SIZE_Q2, DMA_RXBUF_SIZE_Q3, RESERVED16[3], + DMA_RXBUF_SIZE_Q7, CBS_CONTROL, CBS_IDLESLOPE_Q_A, CBS_IDLESLOPE_Q_B, + UPPER_TX_Q_BASE_ADDR, TX_BD_CONTROL, RX_BD_CONTROL, UPPER_RX_Q_BASE_ADDR, + RESERVED17[2], HIDDEN_REG0, HIDDEN_REG1, HIDDEN_REG2, HIDDEN_REG3, + RESERVED18[2], HIDDEN_REG4, HIDDEN_REG5; +}; + +#define ETH0 ((struct ETH_Type *) 0x40490000) + +#define ETH_PKT_SIZE 1536 // Max frame size +#define ETH_DESC_CNT 4 // Descriptors count +#define ETH_DS 2 // Descriptor size (words) + +static uint8_t s_rxbuf[ETH_DESC_CNT][ETH_PKT_SIZE]; +static uint8_t s_txbuf[ETH_DESC_CNT][ETH_PKT_SIZE]; +static uint32_t s_rxdesc[ETH_DESC_CNT][ETH_DS]; // RX descriptors +static uint32_t s_txdesc[ETH_DESC_CNT][ETH_DS]; // TX descriptors +static uint8_t s_txno; // Current TX descriptor +static uint8_t s_rxno; // Current RX descriptor + +static struct mg_tcpip_if *s_ifp; // MIP interface +enum { MG_PHY_ADDR = 0, MG_PHYREG_BCR = 0, MG_PHYREG_BSR = 1 }; + +static uint16_t eth_read_phy(uint8_t addr, uint8_t reg) { + // WRITE1, READ OPERATION, PHY, REG, WRITE10 + ETH0->PHY_MANAGEMENT = MG_BIT(30) | MG_BIT(29) | ((addr & 0xf) << 24) | + ((reg & 0x1f) << 18) | MG_BIT(17); + while ((ETH0->NETWORK_STATUS & MG_BIT(2)) == 0) (void) 0; + return ETH0->PHY_MANAGEMENT & 0xffff; +} + +static void eth_write_phy(uint8_t addr, uint8_t reg, uint16_t val) { + ETH0->PHY_MANAGEMENT = MG_BIT(30) | MG_BIT(28) | ((addr & 0xf) << 24) | + ((reg & 0x1f) << 18) | MG_BIT(17) | val; + while ((ETH0->NETWORK_STATUS & MG_BIT(2)) == 0) (void) 0; +} + +static uint32_t get_clock_rate(struct mg_tcpip_driver_xmc7_data *d) { + // see ETH0 -> NETWORK_CONFIG register + (void) d; + return 3; +} + +static bool mg_tcpip_driver_xmc7_init(struct mg_tcpip_if *ifp) { + struct mg_tcpip_driver_xmc7_data *d = + (struct mg_tcpip_driver_xmc7_data *) ifp->driver_data; + s_ifp = ifp; + + // enable controller, set RGMII mode + ETH0->CTL = MG_BIT(31) | 2; + + uint32_t cr = get_clock_rate(d); + // set NSP change, ignore RX FCS, data bus width, clock rate, Gigabit mode, + // frame length 1536, full duplex, speed + // TODO: enable Gigabit mode (bit 10) only if PHY uses Gigabit link + ETH0->NETWORK_CONFIG = MG_BIT(29) | MG_BIT(26) | MG_BIT(21) | + ((cr & 7) << 18) | MG_BIT(10) | MG_BIT(8) | MG_BIT(4) | + MG_BIT(1) | MG_BIT(0); + + // config DMA settings: Force TX burst, Discard on Error, set RX buffer size + // to 1536, TX_PBUF_SIZE, RX_PBUF_SIZE, AMBA_BURST_LENGTH + ETH0->DMA_CONFIG = + MG_BIT(26) | MG_BIT(24) | (0x18 << 16) | MG_BIT(10) | (3 << 8) | 4; + + // initialize descriptors + for (int i = 0; i < ETH_DESC_CNT; i++) { + s_rxdesc[i][0] = (uint32_t) s_rxbuf[i]; + if (i == ETH_DESC_CNT - 1) { + s_rxdesc[i][0] |= MG_BIT(1); // mark last descriptor + } + + s_txdesc[i][0] = (uint32_t) s_txbuf[i]; + s_txdesc[i][1] = MG_BIT(31); // OWN descriptor + if (i == ETH_DESC_CNT - 1) { + s_txdesc[i][1] |= MG_BIT(30); // mark last descriptor + } + } + ETH0->RECEIVE_Q_PTR = (uint32_t) s_rxdesc; + ETH0->TRANSMIT_Q_PTR = (uint32_t) s_txdesc; + + // disable other queues + ETH0->TRANSMIT_Q2_PTR = 1; + ETH0->TRANSMIT_Q1_PTR = 1; + ETH0->RECEIVE_Q2_PTR = 1; + ETH0->RECEIVE_Q1_PTR = 1; + + // enable interrupts (TX and RX complete) + ETH0->INT_ENABLE = MG_BIT(7) | MG_BIT(1); + + // set MAC address + ETH0->SPEC_ADD1_BOTTOM = + ifp->mac[3] << 24 | ifp->mac[2] << 16 | ifp->mac[1] << 8 | ifp->mac[0]; + ETH0->SPEC_ADD1_TOP = ifp->mac[5] << 8 | ifp->mac[4]; + + // enable MDIO, TX, RX + ETH0->NETWORK_CONTROL = MG_BIT(4) | MG_BIT(3) | MG_BIT(2); + + // start transmission + ETH0->NETWORK_CONTROL |= MG_BIT(9); + + // init phy + struct mg_phy phy = {eth_read_phy, eth_write_phy}; + mg_phy_init(&phy, d->phy_addr, MG_PHY_CLOCKS_MAC); + + (void) d; + return true; +} + +static size_t mg_tcpip_driver_xmc7_tx(const void *buf, size_t len, + struct mg_tcpip_if *ifp) { + if (len > sizeof(s_txbuf[s_txno])) { + MG_ERROR(("Frame too big, %ld", (long) len)); + len = 0; // Frame is too big + } else if (((s_txdesc[s_txno][1] & MG_BIT(31)) == 0)) { + ifp->nerr++; + MG_ERROR(("No free descriptors")); + len = 0; // All descriptors are busy, fail + } else { + memcpy(s_txbuf[s_txno], buf, len); + s_txdesc[s_txno][1] = (s_txno == ETH_DESC_CNT - 1 ? MG_BIT(30) : 0) | + MG_BIT(15) | len; // Last buffer and length + + ETH0->NETWORK_CONTROL |= MG_BIT(9); // enable transmission + if (++s_txno >= ETH_DESC_CNT) s_txno = 0; + } + + MG_DSB(); + ETH0->TRANSMIT_STATUS = ETH0->TRANSMIT_STATUS; + + return len; +} + +static bool mg_tcpip_driver_xmc7_up(struct mg_tcpip_if *ifp) { + struct mg_tcpip_driver_xmc7_data *d = + (struct mg_tcpip_driver_xmc7_data *) ifp->driver_data; + uint8_t speed = MG_PHY_SPEED_10M; + bool up = false, full_duplex = false; + struct mg_phy phy = {eth_read_phy, eth_write_phy}; + up = mg_phy_up(&phy, d->phy_addr, &full_duplex, &speed); + if ((ifp->state == MG_TCPIP_STATE_DOWN) && up) { // link state just went up + MG_DEBUG(("Link is %uM %s-duplex", + speed == MG_PHY_SPEED_10M ? 10 : + (speed == MG_PHY_SPEED_100M ? 100 : 1000), + full_duplex ? "full" : "half")); + } + (void) d; + return up; +} + +void ETH0_IRQHandler(void) { + uint32_t irq_status = ETH0->INT_STATUS; + if (irq_status & MG_BIT(1)) { + for (uint8_t i = 0; i < ETH_DESC_CNT; i++) { + if (s_rxdesc[s_rxno][0] & MG_BIT(0)) { + size_t len = s_rxdesc[s_rxno][1] & (MG_BIT(13) - 1); + MG_INFO(("Receive complete: %ld bytes", len)); + mg_tcpip_qwrite(s_rxbuf[s_rxno], len, s_ifp); + s_rxdesc[s_rxno][0] &= ~MG_BIT(0); // OWN bit: handle control to DMA + if (++s_rxno >= ETH_DESC_CNT) s_rxno = 0; + } + } + } + + ETH0->INT_STATUS = irq_status; +} + +struct mg_tcpip_driver mg_tcpip_driver_xmc7 = {mg_tcpip_driver_xmc7_init, + mg_tcpip_driver_xmc7_tx, NULL, + mg_tcpip_driver_xmc7_up}; +#endif diff --git a/mongoose.h b/mongoose.h index 971a7c0b5b..dc3bf73fd1 100644 --- a/mongoose.h +++ b/mongoose.h @@ -2633,6 +2633,7 @@ extern struct mg_tcpip_driver mg_tcpip_driver_imxrt; extern struct mg_tcpip_driver mg_tcpip_driver_same54; extern struct mg_tcpip_driver mg_tcpip_driver_cmsis; extern struct mg_tcpip_driver mg_tcpip_driver_ra; +extern struct mg_tcpip_driver mg_tcpip_driver_xmc7; // Drivers that require SPI, can use this SPI abstraction struct mg_tcpip_spi { @@ -2936,13 +2937,40 @@ struct mg_tcpip_driver_tm4c_data { #endif -#if MG_ENABLE_TCPIP && defined(MG_ENABLE_DRIVER_W5500) && MG_ENABLE_DRIVER_W5500 +#if MG_ENABLE_TCPIP && defined(MG_ENABLE_DRIVER_XMC7) && MG_ENABLE_DRIVER_XMC7 -#undef MG_ENABLE_TCPIP_DRIVER_INIT -#define MG_ENABLE_TCPIP_DRIVER_INIT 0 +struct mg_tcpip_driver_xmc7_data { + int mdc_cr; // Valid values: -1, 0, 1, 2, 3, 4, 5 + uint8_t phy_addr; +}; + +#ifndef MG_TCPIP_PHY_ADDR +#define MG_TCPIP_PHY_ADDR 0 +#endif +#ifndef MG_DRIVER_MDC_CR +#define MG_DRIVER_MDC_CR 3 #endif +#define MG_TCPIP_DRIVER_INIT(mgr) \ + do { \ + static struct mg_tcpip_driver_xmc7_data driver_data_; \ + static struct mg_tcpip_if mif_; \ + driver_data_.mdc_cr = MG_DRIVER_MDC_CR; \ + driver_data_.phy_addr = MG_TCPIP_PHY_ADDR; \ + mif_.ip = MG_TCPIP_IP; \ + mif_.mask = MG_TCPIP_MASK; \ + mif_.gw = MG_TCPIP_GW; \ + mif_.driver = &mg_tcpip_driver_xmc7; \ + mif_.driver_data = &driver_data_; \ + MG_SET_MAC_ADDRESS(mif_.mac); \ + mg_tcpip_init(mgr, &mif_); \ + MG_INFO(("Driver: xmc7, MAC: %M", mg_print_mac, mif_.mac)); \ + } while (0) + +#endif + + #ifdef __cplusplus } #endif diff --git a/src/drivers/phy.c b/src/drivers/phy.c index 7c3d570b1d..3a11cb9a01 100644 --- a/src/drivers/phy.c +++ b/src/drivers/phy.c @@ -45,6 +45,20 @@ static const char *mg_phy_id_to_str(uint16_t id1, uint16_t id2) { (void) id2; } +static void mg_phy_set_clk_out(struct mg_phy *phy, uint8_t phy_addr) { + uint16_t id1, id2; + id1 = phy->read_reg(phy_addr, MG_PHY_REG_ID1); + id2 = phy->read_reg(phy_addr, MG_PHY_REG_ID2); + + if (id1 == MG_PHY_DP83x && id2 == MG_PHY_DP83867) { + // write 0x10d to IO_MUX_CFG (0x0170) + phy->write_reg(phy_addr, 0x0d, 0x1f); + phy->write_reg(phy_addr, 0x0e, 0x170); + phy->write_reg(phy_addr, 0x0d, 0x401f); + phy->write_reg(phy_addr, 0x0e, 0x10d); + } +} + void mg_phy_init(struct mg_phy *phy, uint8_t phy_addr, uint8_t config) { uint16_t id1, id2; phy->write_reg(phy_addr, MG_PHY_REG_BCR, MG_BIT(15)); // Reset PHY @@ -54,6 +68,10 @@ void mg_phy_init(struct mg_phy *phy, uint8_t phy_addr, uint8_t config) { id2 = phy->read_reg(phy_addr, MG_PHY_REG_ID2); MG_INFO(("PHY ID: %#04x %#04x (%s)", id1, id2, mg_phy_id_to_str(id1, id2))); + if (id1 == MG_PHY_DP83x && id2 == MG_PHY_DP83867) { + mg_phy_set_clk_out(phy, phy_addr); + } + if (config & MG_PHY_CLOCKS_MAC) { // Use PHY crystal oscillator (preserve defaults) // nothing to do diff --git a/src/drivers/xmc7.c b/src/drivers/xmc7.c new file mode 100644 index 0000000000..86cb722f15 --- /dev/null +++ b/src/drivers/xmc7.c @@ -0,0 +1,218 @@ +#include "net_builtin.h" + +#if MG_ENABLE_TCPIP && defined(MG_ENABLE_DRIVER_XMC7) && MG_ENABLE_DRIVER_XMC7 + +struct ETH_Type { + volatile uint32_t CTL, STATUS, RESERVED[1022], NETWORK_CONTROL, + NETWORK_CONFIG, NETWORK_STATUS, USER_IO_REGISTER, DMA_CONFIG, + TRANSMIT_STATUS, RECEIVE_Q_PTR, TRANSMIT_Q_PTR, RECEIVE_STATUS, + INT_STATUS, INT_ENABLE, INT_DISABLE, INT_MASK, PHY_MANAGEMENT, PAUSE_TIME, + TX_PAUSE_QUANTUM, PBUF_TXCUTTHRU, PBUF_RXCUTTHRU, JUMBO_MAX_LENGTH, + EXTERNAL_FIFO_INTERFACE, RESERVED1, AXI_MAX_PIPELINE, RSC_CONTROL, + INT_MODERATION, SYS_WAKE_TIME, RESERVED2[7], HASH_BOTTOM, HASH_TOP, + SPEC_ADD1_BOTTOM, SPEC_ADD1_TOP, SPEC_ADD2_BOTTOM, SPEC_ADD2_TOP, + SPEC_ADD3_BOTTOM, SPEC_ADD3_TOP, SPEC_ADD4_BOTTOM, SPEC_ADD4_TOP, + SPEC_TYPE1, SPEC_TYPE2, SPEC_TYPE3, SPEC_TYPE4, WOL_REGISTER, + STRETCH_RATIO, STACKED_VLAN, TX_PFC_PAUSE, MASK_ADD1_BOTTOM, + MASK_ADD1_TOP, DMA_ADDR_OR_MASK, RX_PTP_UNICAST, TX_PTP_UNICAST, + TSU_NSEC_CMP, TSU_SEC_CMP, TSU_MSB_SEC_CMP, TSU_PTP_TX_MSB_SEC, + TSU_PTP_RX_MSB_SEC, TSU_PEER_TX_MSB_SEC, TSU_PEER_RX_MSB_SEC, + DPRAM_FILL_DBG, REVISION_REG, OCTETS_TXED_BOTTOM, OCTETS_TXED_TOP, + FRAMES_TXED_OK, BROADCAST_TXED, MULTICAST_TXED, PAUSE_FRAMES_TXED, + FRAMES_TXED_64, FRAMES_TXED_65, FRAMES_TXED_128, FRAMES_TXED_256, + FRAMES_TXED_512, FRAMES_TXED_1024, FRAMES_TXED_1519, TX_UNDERRUNS, + SINGLE_COLLISIONS, MULTIPLE_COLLISIONS, EXCESSIVE_COLLISIONS, + LATE_COLLISIONS, DEFERRED_FRAMES, CRS_ERRORS, OCTETS_RXED_BOTTOM, + OCTETS_RXED_TOP, FRAMES_RXED_OK, BROADCAST_RXED, MULTICAST_RXED, + PAUSE_FRAMES_RXED, FRAMES_RXED_64, FRAMES_RXED_65, FRAMES_RXED_128, + FRAMES_RXED_256, FRAMES_RXED_512, FRAMES_RXED_1024, FRAMES_RXED_1519, + UNDERSIZE_FRAMES, EXCESSIVE_RX_LENGTH, RX_JABBERS, FCS_ERRORS, + RX_LENGTH_ERRORS, RX_SYMBOL_ERRORS, ALIGNMENT_ERRORS, RX_RESOURCE_ERRORS, + RX_OVERRUNS, RX_IP_CK_ERRORS, RX_TCP_CK_ERRORS, RX_UDP_CK_ERRORS, + AUTO_FLUSHED_PKTS, RESERVED3, TSU_TIMER_INCR_SUB_NSEC, TSU_TIMER_MSB_SEC, + TSU_STROBE_MSB_SEC, TSU_STROBE_SEC, TSU_STROBE_NSEC, TSU_TIMER_SEC, + TSU_TIMER_NSEC, TSU_TIMER_ADJUST, TSU_TIMER_INCR, TSU_PTP_TX_SEC, + TSU_PTP_TX_NSEC, TSU_PTP_RX_SEC, TSU_PTP_RX_NSEC, TSU_PEER_TX_SEC, + TSU_PEER_TX_NSEC, TSU_PEER_RX_SEC, TSU_PEER_RX_NSEC, PCS_CONTROL, + PCS_STATUS, RESERVED4[2], PCS_AN_ADV, PCS_AN_LP_BASE, PCS_AN_EXP, + PCS_AN_NP_TX, PCS_AN_LP_NP, RESERVED5[6], PCS_AN_EXT_STATUS, RESERVED6[8], + TX_PAUSE_QUANTUM1, TX_PAUSE_QUANTUM2, TX_PAUSE_QUANTUM3, RESERVED7, + RX_LPI, RX_LPI_TIME, TX_LPI, TX_LPI_TIME, DESIGNCFG_DEBUG1, + DESIGNCFG_DEBUG2, DESIGNCFG_DEBUG3, DESIGNCFG_DEBUG4, DESIGNCFG_DEBUG5, + DESIGNCFG_DEBUG6, DESIGNCFG_DEBUG7, DESIGNCFG_DEBUG8, DESIGNCFG_DEBUG9, + DESIGNCFG_DEBUG10, RESERVED8[22], SPEC_ADD5_BOTTOM, SPEC_ADD5_TOP, + RESERVED9[60], SPEC_ADD36_BOTTOM, SPEC_ADD36_TOP, INT_Q1_STATUS, + INT_Q2_STATUS, INT_Q3_STATUS, RESERVED10[11], INT_Q15_STATUS, RESERVED11, + TRANSMIT_Q1_PTR, TRANSMIT_Q2_PTR, TRANSMIT_Q3_PTR, RESERVED12[11], + TRANSMIT_Q15_PTR, RESERVED13, RECEIVE_Q1_PTR, RECEIVE_Q2_PTR, + RECEIVE_Q3_PTR, RESERVED14[3], RECEIVE_Q7_PTR, RESERVED15, + DMA_RXBUF_SIZE_Q1, DMA_RXBUF_SIZE_Q2, DMA_RXBUF_SIZE_Q3, RESERVED16[3], + DMA_RXBUF_SIZE_Q7, CBS_CONTROL, CBS_IDLESLOPE_Q_A, CBS_IDLESLOPE_Q_B, + UPPER_TX_Q_BASE_ADDR, TX_BD_CONTROL, RX_BD_CONTROL, UPPER_RX_Q_BASE_ADDR, + RESERVED17[2], HIDDEN_REG0, HIDDEN_REG1, HIDDEN_REG2, HIDDEN_REG3, + RESERVED18[2], HIDDEN_REG4, HIDDEN_REG5; +}; + +#define ETH0 ((struct ETH_Type *) 0x40490000) + +#define ETH_PKT_SIZE 1536 // Max frame size +#define ETH_DESC_CNT 4 // Descriptors count +#define ETH_DS 2 // Descriptor size (words) + +static uint8_t s_rxbuf[ETH_DESC_CNT][ETH_PKT_SIZE]; +static uint8_t s_txbuf[ETH_DESC_CNT][ETH_PKT_SIZE]; +static uint32_t s_rxdesc[ETH_DESC_CNT][ETH_DS]; // RX descriptors +static uint32_t s_txdesc[ETH_DESC_CNT][ETH_DS]; // TX descriptors +static uint8_t s_txno; // Current TX descriptor +static uint8_t s_rxno; // Current RX descriptor + +static struct mg_tcpip_if *s_ifp; // MIP interface +enum { MG_PHY_ADDR = 0, MG_PHYREG_BCR = 0, MG_PHYREG_BSR = 1 }; + +static uint16_t eth_read_phy(uint8_t addr, uint8_t reg) { + // WRITE1, READ OPERATION, PHY, REG, WRITE10 + ETH0->PHY_MANAGEMENT = MG_BIT(30) | MG_BIT(29) | ((addr & 0xf) << 24) | + ((reg & 0x1f) << 18) | MG_BIT(17); + while ((ETH0->NETWORK_STATUS & MG_BIT(2)) == 0) (void) 0; + return ETH0->PHY_MANAGEMENT & 0xffff; +} + +static void eth_write_phy(uint8_t addr, uint8_t reg, uint16_t val) { + ETH0->PHY_MANAGEMENT = MG_BIT(30) | MG_BIT(28) | ((addr & 0xf) << 24) | + ((reg & 0x1f) << 18) | MG_BIT(17) | val; + while ((ETH0->NETWORK_STATUS & MG_BIT(2)) == 0) (void) 0; +} + +static uint32_t get_clock_rate(struct mg_tcpip_driver_xmc7_data *d) { + // see ETH0 -> NETWORK_CONFIG register + (void) d; + return 3; +} + +static bool mg_tcpip_driver_xmc7_init(struct mg_tcpip_if *ifp) { + struct mg_tcpip_driver_xmc7_data *d = + (struct mg_tcpip_driver_xmc7_data *) ifp->driver_data; + s_ifp = ifp; + + // enable controller, set RGMII mode + ETH0->CTL = MG_BIT(31) | 2; + + uint32_t cr = get_clock_rate(d); + // set NSP change, ignore RX FCS, data bus width, clock rate, Gigabit mode, + // frame length 1536, full duplex, speed + // TODO: enable Gigabit mode (bit 10) only if PHY uses Gigabit link + ETH0->NETWORK_CONFIG = MG_BIT(29) | MG_BIT(26) | MG_BIT(21) | + ((cr & 7) << 18) | MG_BIT(10) | MG_BIT(8) | MG_BIT(4) | + MG_BIT(1) | MG_BIT(0); + + // config DMA settings: Force TX burst, Discard on Error, set RX buffer size + // to 1536, TX_PBUF_SIZE, RX_PBUF_SIZE, AMBA_BURST_LENGTH + ETH0->DMA_CONFIG = + MG_BIT(26) | MG_BIT(24) | (0x18 << 16) | MG_BIT(10) | (3 << 8) | 4; + + // initialize descriptors + for (int i = 0; i < ETH_DESC_CNT; i++) { + s_rxdesc[i][0] = (uint32_t) s_rxbuf[i]; + if (i == ETH_DESC_CNT - 1) { + s_rxdesc[i][0] |= MG_BIT(1); // mark last descriptor + } + + s_txdesc[i][0] = (uint32_t) s_txbuf[i]; + s_txdesc[i][1] = MG_BIT(31); // OWN descriptor + if (i == ETH_DESC_CNT - 1) { + s_txdesc[i][1] |= MG_BIT(30); // mark last descriptor + } + } + ETH0->RECEIVE_Q_PTR = (uint32_t) s_rxdesc; + ETH0->TRANSMIT_Q_PTR = (uint32_t) s_txdesc; + + // disable other queues + ETH0->TRANSMIT_Q2_PTR = 1; + ETH0->TRANSMIT_Q1_PTR = 1; + ETH0->RECEIVE_Q2_PTR = 1; + ETH0->RECEIVE_Q1_PTR = 1; + + // enable interrupts (TX and RX complete) + ETH0->INT_ENABLE = MG_BIT(7) | MG_BIT(1); + + // set MAC address + ETH0->SPEC_ADD1_BOTTOM = + ifp->mac[3] << 24 | ifp->mac[2] << 16 | ifp->mac[1] << 8 | ifp->mac[0]; + ETH0->SPEC_ADD1_TOP = ifp->mac[5] << 8 | ifp->mac[4]; + + // enable MDIO, TX, RX + ETH0->NETWORK_CONTROL = MG_BIT(4) | MG_BIT(3) | MG_BIT(2); + + // start transmission + ETH0->NETWORK_CONTROL |= MG_BIT(9); + + // init phy + struct mg_phy phy = {eth_read_phy, eth_write_phy}; + mg_phy_init(&phy, d->phy_addr, MG_PHY_CLOCKS_MAC); + + (void) d; + return true; +} + +static size_t mg_tcpip_driver_xmc7_tx(const void *buf, size_t len, + struct mg_tcpip_if *ifp) { + if (len > sizeof(s_txbuf[s_txno])) { + MG_ERROR(("Frame too big, %ld", (long) len)); + len = 0; // Frame is too big + } else if (((s_txdesc[s_txno][1] & MG_BIT(31)) == 0)) { + ifp->nerr++; + MG_ERROR(("No free descriptors")); + len = 0; // All descriptors are busy, fail + } else { + memcpy(s_txbuf[s_txno], buf, len); + s_txdesc[s_txno][1] = (s_txno == ETH_DESC_CNT - 1 ? MG_BIT(30) : 0) | + MG_BIT(15) | len; // Last buffer and length + + ETH0->NETWORK_CONTROL |= MG_BIT(9); // enable transmission + if (++s_txno >= ETH_DESC_CNT) s_txno = 0; + } + + MG_DSB(); + ETH0->TRANSMIT_STATUS = ETH0->TRANSMIT_STATUS; + + return len; +} + +static bool mg_tcpip_driver_xmc7_up(struct mg_tcpip_if *ifp) { + struct mg_tcpip_driver_xmc7_data *d = + (struct mg_tcpip_driver_xmc7_data *) ifp->driver_data; + uint8_t speed = MG_PHY_SPEED_10M; + bool up = false, full_duplex = false; + struct mg_phy phy = {eth_read_phy, eth_write_phy}; + up = mg_phy_up(&phy, d->phy_addr, &full_duplex, &speed); + if ((ifp->state == MG_TCPIP_STATE_DOWN) && up) { // link state just went up + MG_DEBUG(("Link is %uM %s-duplex", + speed == MG_PHY_SPEED_10M ? 10 : + (speed == MG_PHY_SPEED_100M ? 100 : 1000), + full_duplex ? "full" : "half")); + } + (void) d; + return up; +} + +void ETH0_IRQHandler(void) { + uint32_t irq_status = ETH0->INT_STATUS; + if (irq_status & MG_BIT(1)) { + for (uint8_t i = 0; i < ETH_DESC_CNT; i++) { + if (s_rxdesc[s_rxno][0] & MG_BIT(0)) { + size_t len = s_rxdesc[s_rxno][1] & (MG_BIT(13) - 1); + MG_INFO(("Receive complete: %ld bytes", len)); + mg_tcpip_qwrite(s_rxbuf[s_rxno], len, s_ifp); + s_rxdesc[s_rxno][0] &= ~MG_BIT(0); // OWN bit: handle control to DMA + if (++s_rxno >= ETH_DESC_CNT) s_rxno = 0; + } + } + } + + ETH0->INT_STATUS = irq_status; +} + +struct mg_tcpip_driver mg_tcpip_driver_xmc7 = {mg_tcpip_driver_xmc7_init, + mg_tcpip_driver_xmc7_tx, NULL, + mg_tcpip_driver_xmc7_up}; +#endif diff --git a/src/drivers/xmc7.h b/src/drivers/xmc7.h new file mode 100644 index 0000000000..c59fc203fe --- /dev/null +++ b/src/drivers/xmc7.h @@ -0,0 +1,35 @@ +#pragma once + +#if MG_ENABLE_TCPIP && defined(MG_ENABLE_DRIVER_XMC7) && MG_ENABLE_DRIVER_XMC7 + +struct mg_tcpip_driver_xmc7_data { + int mdc_cr; // Valid values: -1, 0, 1, 2, 3, 4, 5 + uint8_t phy_addr; +}; + +#ifndef MG_TCPIP_PHY_ADDR +#define MG_TCPIP_PHY_ADDR 0 +#endif + +#ifndef MG_DRIVER_MDC_CR +#define MG_DRIVER_MDC_CR 3 +#endif + +#define MG_TCPIP_DRIVER_INIT(mgr) \ + do { \ + static struct mg_tcpip_driver_xmc7_data driver_data_; \ + static struct mg_tcpip_if mif_; \ + driver_data_.mdc_cr = MG_DRIVER_MDC_CR; \ + driver_data_.phy_addr = MG_TCPIP_PHY_ADDR; \ + mif_.ip = MG_TCPIP_IP; \ + mif_.mask = MG_TCPIP_MASK; \ + mif_.gw = MG_TCPIP_GW; \ + mif_.driver = &mg_tcpip_driver_xmc7; \ + mif_.driver_data = &driver_data_; \ + MG_SET_MAC_ADDRESS(mif_.mac); \ + mg_tcpip_init(mgr, &mif_); \ + MG_INFO(("Driver: xmc7, MAC: %M", mg_print_mac, mif_.mac)); \ + } while (0) + +#endif + diff --git a/src/net_builtin.h b/src/net_builtin.h index b5ef0c938f..024d457f83 100644 --- a/src/net_builtin.h +++ b/src/net_builtin.h @@ -60,6 +60,7 @@ extern struct mg_tcpip_driver mg_tcpip_driver_imxrt; extern struct mg_tcpip_driver mg_tcpip_driver_same54; extern struct mg_tcpip_driver mg_tcpip_driver_cmsis; extern struct mg_tcpip_driver mg_tcpip_driver_ra; +extern struct mg_tcpip_driver mg_tcpip_driver_xmc7; // Drivers that require SPI, can use this SPI abstraction struct mg_tcpip_spi {