diff --git a/examples/stm32/nucleo-h563zi-make-freertos-builtin/FreeRTOSConfig.h b/examples/stm32/nucleo-h563zi-make-freertos-builtin/FreeRTOSConfig.h new file mode 100644 index 00000000..5173eddb --- /dev/null +++ b/examples/stm32/nucleo-h563zi-make-freertos-builtin/FreeRTOSConfig.h @@ -0,0 +1,44 @@ +#pragma once + +#include "hal.h" + +#define configUSE_PREEMPTION 1 +#define configCPU_CLOCK_HZ CPU_FREQUENCY +#define configTICK_RATE_HZ 1000 +#define configMAX_PRIORITIES 5 +#define configUSE_16_BIT_TICKS 0 +#define configUSE_TICK_HOOK 0 +#define configUSE_IDLE_HOOK 0 +#define configUSE_TIMERS 0 +#define configUSE_CO_ROUTINES 0 +#define configUSE_MALLOC_FAILED_HOOK 0 +#define configMINIMAL_STACK_SIZE 128 +#define configTOTAL_HEAP_SIZE (1024 * 128) +#define INCLUDE_vTaskDelay 1 +#define INCLUDE_xTaskGetSchedulerState 1 // trying + +#ifdef __NVIC_PRIO_BITS +#define configPRIO_BITS __NVIC_PRIO_BITS +#else +#define configPRIO_BITS 4 +#endif +#define configLIBRARY_LOWEST_INTERRUPT_PRIORITY 15 +#define configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY 5 +#define configKERNEL_INTERRUPT_PRIORITY \ + (configLIBRARY_LOWEST_INTERRUPT_PRIORITY << (8 - configPRIO_BITS)) + +#define configMAX_SYSCALL_INTERRUPT_PRIORITY \ + (configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS)) + +#define configASSERT(expr) \ + if (!(expr)) printf("FAILURE %s:%d: %s\n", __FILE__, __LINE__, #expr) + +// https://www.freertos.org/2020/04/using-freertos-on-armv8-m-microcontrollers.html +#define configENABLE_FPU 1 +#define configENABLE_MPU 0 +#define configENABLE_TRUSTZONE 0 +#define configRUN_FREERTOS_SECURE_ONLY 0 + +//#define vPortSVCHandler SVC_Handler +//#define xPortPendSVHandler PendSV_Handler +//#define xPortSysTickHandler SysTick_Handler diff --git a/examples/stm32/nucleo-h563zi-make-freertos-builtin/Makefile b/examples/stm32/nucleo-h563zi-make-freertos-builtin/Makefile new file mode 100644 index 00000000..48ec71c2 --- /dev/null +++ b/examples/stm32/nucleo-h563zi-make-freertos-builtin/Makefile @@ -0,0 +1,59 @@ +CFLAGS = -W -Wall -Wextra -Werror -Wundef -Wshadow -Wdouble-promotion +CFLAGS += -Wformat-truncation -fno-common -Wconversion -Wno-sign-conversion +CFLAGS += -g3 -Os -ffunction-sections -fdata-sections +CFLAGS += -I. -Icmsis_core/CMSIS/Core/Include -Icmsis_h5/Include +CFLAGS += -mcpu=cortex-m33 -mthumb -mfpu=fpv5-sp-d16 -mfloat-abi=hard +LDFLAGS ?= -Tlink.ld -nostdlib -nostartfiles --specs nano.specs -lc -lgcc -Wl,--gc-sections -Wl,-Map=$@.map + +SOURCES = main.c syscalls.c sysinit.c +SOURCES += cmsis_h5/Source/Templates/gcc/startup_stm32h563xx.s # ST startup file. Compiler-dependent! + +# FreeRTOS. H5 has a Cortex-M33 (ARMv8) core, the CM4F port can be used if TrustZone and the MPU are not to be used, see H7 example +SOURCES += FreeRTOS-Kernel/portable/MemMang/heap_4.c +SOURCES += FreeRTOS-Kernel/portable/GCC/ARM_CM33_NTZ/non_secure/port.c +SOURCES += FreeRTOS-Kernel/portable/GCC/ARM_CM33_NTZ/non_secure/portasm.c +CFLAGS += -IFreeRTOS-Kernel/include +CFLAGS += -IFreeRTOS-Kernel/portable/GCC/ARM_CM33_NTZ/non_secure -Wno-conversion -Wno-unused-parameter + +SOURCES += mongoose.c net.c packed_fs.c +CFLAGS += $(CFLAGS_EXTRA) # Mongoose options are defined in mongoose_custom.h + +# Example specific build options. See README.md +CFLAGS += -DHTTP_URL=\"http://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: FreeRTOS-Kernel cmsis_core cmsis_h5 $(SOURCES) hal.h link.ld mongoose_custom.h FreeRTOSConfig.h Makefile + arm-none-eabi-gcc $(SOURCES) $(wildcard FreeRTOS-Kernel/*.c) $(CFLAGS) $(LDFLAGS) -o $@ + +flash: firmware.bin + st-flash --debug --freq=200 --reset write $< 0x8000000 + +cmsis_core: # ARM CMSIS core headers + git clone --depth 1 -b 5.9.0 https://github.com/ARM-software/CMSIS_5 $@ +cmsis_h5: # ST CMSIS headers for STM32H5 series + git clone --depth 1 -b main https://github.com/STMicroelectronics/cmsis_device_h5 $@ +FreeRTOS-Kernel: # FreeRTOS sources + git clone --depth 1 -b V10.5.0 https://github.com/FreeRTOS/FreeRTOS-Kernel $@ + +# Automated remote test. Requires env variable VCON_API_KEY set. See https://vcon.io/automated-firmware-tests/ +DEVICE_URL ?= https://dash.vcon.io/api/v3/devices/11 +update: firmware.bin + curl --fail-with-body -su :$(VCON_API_KEY) $(DEVICE_URL)/ota --data-binary @$< + +test update: CFLAGS += -DUART_DEBUG=USART1 +test: update + curl --fail-with-body -su :$(VCON_API_KEY) $(DEVICE_URL)/tx?t=5 | tee /tmp/output.txt + grep 'READY, IP:' /tmp/output.txt # Check for network init + +clean: + $(RM) firmware.* *.su cmsis_core cmsis_h5 FreeRTOS-Kernel diff --git a/examples/stm32/nucleo-h563zi-make-freertos-builtin/README.md b/examples/stm32/nucleo-h563zi-make-freertos-builtin/README.md new file mode 100644 index 00000000..db2f9a4e --- /dev/null +++ b/examples/stm32/nucleo-h563zi-make-freertos-builtin/README.md @@ -0,0 +1,3 @@ +# FreeRTOS web device dashboard on NUCLEO-H563ZI + +See https://mongoose.ws/tutorials/stm32/all-make-freertos-builtin/ diff --git a/examples/stm32/nucleo-h563zi-make-freertos-builtin/hal.h b/examples/stm32/nucleo-h563zi-make-freertos-builtin/hal.h new file mode 100644 index 00000000..138b42a8 --- /dev/null +++ b/examples/stm32/nucleo-h563zi-make-freertos-builtin/hal.h @@ -0,0 +1,174 @@ +// Copyright (c) 2022-2023 Cesanta Software Limited +// All rights reserved +// +// Datasheet: RM0481, devboard manual: UM3115 +// https://www.st.com/resource/en/reference_manual/rm0481-stm32h563h573-and-stm32h562-armbased-32bit-mcus-stmicroelectronics.pdf +// Alternate functions: https://www.st.com/resource/en/datasheet/stm32h563vi.pdf + +#pragma once + +#include + +#include +#include +#include +#include +#include + +#define BIT(x) (1UL << (x)) +#define SETBITS(R, CLEARMASK, SETMASK) (R) = ((R) & ~(CLEARMASK)) | (SETMASK) +#define PIN(bank, num) ((((bank) - 'A') << 8) | (num)) +#define PINNO(pin) (pin & 255) +#define PINBANK(pin) (pin >> 8) + +#define LED1 PIN('B', 0) // On-board LED pin (green) +#define LED2 PIN('F', 4) // On-board LED pin (yellow) +#define LED3 PIN('G', 4) // On-board LED pin (red) + +#define LED LED2 // Use yellow LED for blinking + +// System clock (11.4, Figure 48; 11.4.5, Figure 51; 11.4.8 +// CPU_FREQUENCY <= 250 MHz; (SYS_FREQUENCY / HPRE) ; hclk = CPU_FREQUENCY +// APB clocks <= 250 MHz. Configure flash latency (WS) in accordance to hclk +// freq (7.3.4, Table 37) +enum { + HPRE = 7, // register value, divisor value = BIT(value - 7) = / 1 + PPRE1 = 4, // register values, divisor value = BIT(value - 3) = / 2 + PPRE2 = 4, + PPRE3 = 4, +}; +// Make sure your chip package uses the internal LDO, otherwise set PLL1_N = 200 +enum { PLL1_HSI = 64, PLL1_M = 32, PLL1_N = 250, PLL1_P = 2 }; +#define FLASH_LATENCY 0x25 // WRHIGHFREQ LATENCY +#define CPU_FREQUENCY ((PLL1_HSI * PLL1_N / PLL1_M / PLL1_P / (BIT(HPRE - 7))) * 1000000) +#define AHB_FREQUENCY CPU_FREQUENCY +#define APB2_FREQUENCY (AHB_FREQUENCY / (BIT(PPRE2 - 3))) +#define APB1_FREQUENCY (AHB_FREQUENCY / (BIT(PPRE1 - 3))) + +static inline void spin(volatile uint32_t n) { + while (n--) (void) 0; +} + +enum { GPIO_MODE_INPUT, GPIO_MODE_OUTPUT, GPIO_MODE_AF, GPIO_MODE_ANALOG }; +enum { GPIO_OTYPE_PUSH_PULL, GPIO_OTYPE_OPEN_DRAIN }; +enum { GPIO_SPEED_LOW, GPIO_SPEED_MEDIUM, GPIO_SPEED_HIGH, GPIO_SPEED_INSANE }; +enum { GPIO_PULL_NONE, GPIO_PULL_UP, GPIO_PULL_DOWN }; + +#define GPIO(N) ((GPIO_TypeDef *) ((GPIOA_BASE_NS) + 0x400 * (N))) + +static GPIO_TypeDef *gpio_bank(uint16_t pin) { + return GPIO(PINBANK(pin)); +} +static inline void gpio_toggle(uint16_t pin) { + GPIO_TypeDef *gpio = gpio_bank(pin); + uint32_t mask = BIT(PINNO(pin)); + gpio->BSRR = mask << (gpio->ODR & mask ? 16 : 0); +} +static inline int gpio_read(uint16_t pin) { + return gpio_bank(pin)->IDR & BIT(PINNO(pin)) ? 1 : 0; +} +static inline void gpio_write(uint16_t pin, bool val) { + GPIO_TypeDef *gpio = gpio_bank(pin); + gpio->BSRR = BIT(PINNO(pin)) << (val ? 0 : 16); +} +static inline void gpio_init(uint16_t pin, uint8_t mode, uint8_t type, + uint8_t speed, uint8_t pull, uint8_t af) { + GPIO_TypeDef *gpio = gpio_bank(pin); + uint8_t n = (uint8_t) (PINNO(pin)); + RCC->AHB2ENR |= BIT(PINBANK(pin)); // Enable GPIO clock + SETBITS(gpio->OTYPER, 1UL << n, ((uint32_t) type) << n); + SETBITS(gpio->OSPEEDR, 3UL << (n * 2), ((uint32_t) speed) << (n * 2)); + SETBITS(gpio->PUPDR, 3UL << (n * 2), ((uint32_t) pull) << (n * 2)); + SETBITS(gpio->AFR[n >> 3], 15UL << ((n & 7) * 4), + ((uint32_t) af) << ((n & 7) * 4)); + SETBITS(gpio->MODER, 3UL << (n * 2), ((uint32_t) mode) << (n * 2)); +} +static inline void gpio_input(uint16_t pin) { + gpio_init(pin, GPIO_MODE_INPUT, GPIO_OTYPE_PUSH_PULL, GPIO_SPEED_HIGH, + GPIO_PULL_NONE, 0); +} +static inline void gpio_output(uint16_t pin) { + gpio_init(pin, GPIO_MODE_OUTPUT, GPIO_OTYPE_PUSH_PULL, GPIO_SPEED_HIGH, + GPIO_PULL_NONE, 0); +} + +#ifndef UART_DEBUG +#define UART_DEBUG USART3 +#endif + +static inline bool uart_init(USART_TypeDef *uart, unsigned long baud) { + uint8_t af = 7; // Alternate function + uint16_t rx = 0, tx = 0; // pins + uint32_t freq = 0; // Bus frequency. UART1 is on APB2, rest on APB1 + + if (uart == USART1) { + freq = APB2_FREQUENCY, RCC->APB2ENR |= RCC_APB2ENR_USART1EN; + tx = PIN('A', 9), rx = PIN('A', 10); + } else if (uart == USART2) { + freq = APB1_FREQUENCY, RCC->APB1LENR |= RCC_APB1LENR_USART2EN; + tx = PIN('A', 2), rx = PIN('A', 3); + } else if (uart == USART3) { + freq = APB1_FREQUENCY, RCC->APB1LENR |= RCC_APB1LENR_USART3EN; + tx = PIN('D', 8), rx = PIN('D', 9); + } else { + return false; + } + gpio_init(tx, GPIO_MODE_AF, GPIO_OTYPE_PUSH_PULL, GPIO_SPEED_HIGH, 0, af); + gpio_init(rx, GPIO_MODE_AF, GPIO_OTYPE_PUSH_PULL, GPIO_SPEED_HIGH, 0, af); + uart->CR1 = 0; // Disable UART + uart->BRR = freq / baud; // Set baud rate + uart->CR1 = USART_CR1_RE | USART_CR1_TE; // Set mode to TX & RX + uart->CR1 |= USART_CR1_UE; // Enable UART + return true; +} +static inline void uart_write_byte(USART_TypeDef *uart, uint8_t byte) { + uart->TDR = byte; + while ((uart->ISR & BIT(7)) == 0) spin(1); +} +static inline void uart_write_buf(USART_TypeDef *uart, char *buf, size_t len) { + while (len-- > 0) uart_write_byte(uart, *(uint8_t *) buf++); +} +static inline int uart_read_ready(USART_TypeDef *uart) { + return uart->ISR & BIT(5); // If RXNE bit is set, data is ready +} +static inline uint8_t uart_read_byte(USART_TypeDef *uart) { + return (uint8_t) (uart->RDR & 255); +} + +static inline void rng_init(void) { + RCC->CCIPR5 |= RCC_CCIPR5_RNGSEL_0; // RNG clock source pll1_q_ck + RCC->AHB2ENR |= RCC_AHB2ENR_RNGEN; // Enable RNG clock + RNG->CR |= RNG_CR_RNGEN; // Enable RNG +} +static inline uint32_t rng_read(void) { + while ((RNG->SR & RNG_SR_DRDY) == 0) spin(1); + return RNG->DR; +} + +static inline bool ldo_is_on(void) { + return (PWR->SCCR & PWR_SCCR_LDOEN) == PWR_SCCR_LDOEN; +} + +static inline void ethernet_init(void) { + // Initialise Ethernet. Enable MAC GPIO pins, see UM3115 section 10.7 + uint16_t pins[] = {PIN('A', 1), PIN('A', 2), PIN('A', 7), + PIN('B', 15), PIN('C', 1), PIN('C', 4), + PIN('C', 5), PIN('G', 11), PIN('G', 13)}; + for (size_t i = 0; i < sizeof(pins) / sizeof(pins[0]); i++) { + gpio_init(pins[i], GPIO_MODE_AF, GPIO_OTYPE_PUSH_PULL, GPIO_SPEED_INSANE, + GPIO_PULL_NONE, 11); // 11 is the Ethernet function + } + NVIC_EnableIRQ(ETH_IRQn); // Setup Ethernet IRQ handler + RCC->APB3ENR |= RCC_APB3ENR_SBSEN; // Enable SBS clock + SETBITS(SBS->PMCR, SBS_PMCR_ETH_SEL_PHY, SBS_PMCR_ETH_SEL_PHY_2); // RMII + RCC->AHB1ENR |= RCC_AHB1ENR_ETHEN | RCC_AHB1ENR_ETHRXEN | RCC_AHB1ENR_ETHTXEN; +} + +#define UUID ((uint32_t *) UID_BASE) // Unique 96-bit chip ID. TRM 59.1 + +// Helper macro for MAC generation, byte reads not allowed +#define GENERATE_LOCALLY_ADMINISTERED_MAC() \ + { \ + 2, UUID[0] & 255, (UUID[0] >> 10) & 255, (UUID[0] >> 19) & 255, \ + UUID[1] & 255, UUID[2] & 255 \ + } diff --git a/examples/stm32/nucleo-h563zi-make-freertos-builtin/link.ld b/examples/stm32/nucleo-h563zi-make-freertos-builtin/link.ld new file mode 100644 index 00000000..b9e091b8 --- /dev/null +++ b/examples/stm32/nucleo-h563zi-make-freertos-builtin/link.ld @@ -0,0 +1,29 @@ +ENTRY(Reset_Handler); +MEMORY { + flash(rx) : ORIGIN = 0x08000000, LENGTH = 2048k + sram(rwx) : ORIGIN = 0x20000000, LENGTH = 640k +} +_estack = ORIGIN(sram) + LENGTH(sram); /* stack points to end of SRAM */ + +SECTIONS { + .vectors : { KEEP(*(.isr_vector)) } > flash + .text : { *(.text* .text.*) } > flash + .rodata : { *(.rodata*) } > flash + + .data : { + _sdata = .; /* for init_ram() */ + *(.first_data) + *(.data SORT(.data.*)) + _edata = .; /* for init_ram() */ + } > sram AT > flash + _sidata = LOADADDR(.data); + + .bss : { + _sbss = .; /* for init_ram() */ + *(.bss SORT(.bss.*) COMMON) + _ebss = .; /* for init_ram() */ + } > sram + + . = ALIGN(8); + _end = .; /* for cmsis_gcc.h and init_ram() */ +} diff --git a/examples/stm32/nucleo-h563zi-make-freertos-builtin/main.c b/examples/stm32/nucleo-h563zi-make-freertos-builtin/main.c new file mode 100644 index 00000000..272030a9 --- /dev/null +++ b/examples/stm32/nucleo-h563zi-make-freertos-builtin/main.c @@ -0,0 +1,75 @@ +// Copyright (c) 2023 Cesanta Software Limited +// All rights reserved + +#include "hal.h" +#include "mongoose.h" +#include "net.h" + +#define BLINK_PERIOD_MS 1000 // LED blinking period in millis + +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)); + } +} + +static void timer_fn(void *arg) { + struct mg_tcpip_if *ifp = arg; // And show + const char *names[] = {"down", "up", "req", "ready"}; // network stats + MG_INFO(("Ethernet: %s, IP: %M, rx:%u, tx:%u, dr:%u, er:%u", + names[ifp->state], mg_print_ip4, &ifp->ip, ifp->nrecv, ifp->nsent, + ifp->ndrop, ifp->nerr)); +} + +static void server(void *args) { + struct mg_mgr mgr; // Initialise Mongoose event manager + mg_mgr_init(&mgr); // and attach it to the interface + mg_log_set(MG_LL_DEBUG); // Set log level + + // Initialise Mongoose network stack + ethernet_init(); + struct mg_tcpip_driver_stm32h_data driver_data = {.mdc_cr = 4}; + struct mg_tcpip_if mif = {.mac = GENERATE_LOCALLY_ADMINISTERED_MAC(), + // Uncomment below for static configuration: + // .ip = mg_htonl(MG_U32(192, 168, 0, 223)), + // .mask = mg_htonl(MG_U32(255, 255, 255, 0)), + // .gw = mg_htonl(MG_U32(192, 168, 0, 1)), + .driver = &mg_tcpip_driver_stm32h, + .driver_data = &driver_data}; + mg_tcpip_init(&mgr, &mif); + mg_timer_add(&mgr, BLINK_PERIOD_MS, MG_TIMER_REPEAT, timer_fn, &mif); + + MG_INFO(("MAC: %M. Waiting for IP...", mg_print_mac, mif.mac)); + while (mif.state != MG_TCPIP_STATE_READY) { + mg_mgr_poll(&mgr, 0); + } + + MG_INFO(("Initialising application...")); + web_init(&mgr); + + MG_INFO(("Starting event loop")); + for (;;) mg_mgr_poll(&mgr, 1); // Infinite event loop + (void) args; +} + +static void blinker(void *args) { + gpio_init(LED, GPIO_MODE_OUTPUT, GPIO_OTYPE_PUSH_PULL, GPIO_SPEED_MEDIUM, + GPIO_PULL_NONE, 0); + for (;;) { + gpio_toggle(LED); + vTaskDelay(pdMS_TO_TICKS(BLINK_PERIOD_MS)); + } + (void) args; +} + +int main(void) { + uart_init(UART_DEBUG, 115200); // Initialise UART + + // Start tasks. NOTE: stack sizes are in 32-bit words + xTaskCreate(blinker, "blinker", 128, ":)", configMAX_PRIORITIES - 1, NULL); + xTaskCreate(server, "server", 2048, 0, configMAX_PRIORITIES - 1, NULL); + + vTaskStartScheduler(); // This blocks + return 0; +} diff --git a/examples/stm32/nucleo-h563zi-make-freertos-builtin/mongoose.c b/examples/stm32/nucleo-h563zi-make-freertos-builtin/mongoose.c new file mode 120000 index 00000000..5e522bbc --- /dev/null +++ b/examples/stm32/nucleo-h563zi-make-freertos-builtin/mongoose.c @@ -0,0 +1 @@ +../../../mongoose.c \ No newline at end of file diff --git a/examples/stm32/nucleo-h563zi-make-freertos-builtin/mongoose.h b/examples/stm32/nucleo-h563zi-make-freertos-builtin/mongoose.h new file mode 120000 index 00000000..ee4ac823 --- /dev/null +++ b/examples/stm32/nucleo-h563zi-make-freertos-builtin/mongoose.h @@ -0,0 +1 @@ +../../../mongoose.h \ No newline at end of file diff --git a/examples/stm32/nucleo-h563zi-make-freertos-builtin/mongoose_custom.h b/examples/stm32/nucleo-h563zi-make-freertos-builtin/mongoose_custom.h new file mode 100644 index 00000000..29f88e0e --- /dev/null +++ b/examples/stm32/nucleo-h563zi-make-freertos-builtin/mongoose_custom.h @@ -0,0 +1,12 @@ +#pragma once + +#include // we are not using lwIP + +// See https://mongoose.ws/documentation/#build-options +#define MG_ARCH MG_ARCH_FREERTOS +#define MG_ENABLE_TCPIP 1 +#define MG_ENABLE_DRIVER_STM32H 1 +#define MG_IO_SIZE 256 +#define MG_ENABLE_CUSTOM_RANDOM 1 +#define MG_ENABLE_PACKED_FS 1 + diff --git a/examples/stm32/nucleo-h563zi-make-freertos-builtin/net.c b/examples/stm32/nucleo-h563zi-make-freertos-builtin/net.c new file mode 120000 index 00000000..fe0e6f06 --- /dev/null +++ b/examples/stm32/nucleo-h563zi-make-freertos-builtin/net.c @@ -0,0 +1 @@ +../../device-dashboard/net.c \ No newline at end of file diff --git a/examples/stm32/nucleo-h563zi-make-freertos-builtin/net.h b/examples/stm32/nucleo-h563zi-make-freertos-builtin/net.h new file mode 120000 index 00000000..9de896ef --- /dev/null +++ b/examples/stm32/nucleo-h563zi-make-freertos-builtin/net.h @@ -0,0 +1 @@ +../../device-dashboard/net.h \ No newline at end of file diff --git a/examples/stm32/nucleo-h563zi-make-freertos-builtin/packed_fs.c b/examples/stm32/nucleo-h563zi-make-freertos-builtin/packed_fs.c new file mode 120000 index 00000000..e06bf092 --- /dev/null +++ b/examples/stm32/nucleo-h563zi-make-freertos-builtin/packed_fs.c @@ -0,0 +1 @@ +../../device-dashboard/packed_fs.c \ No newline at end of file diff --git a/examples/stm32/nucleo-h563zi-make-freertos-builtin/syscalls.c b/examples/stm32/nucleo-h563zi-make-freertos-builtin/syscalls.c new file mode 100644 index 00000000..be3210aa --- /dev/null +++ b/examples/stm32/nucleo-h563zi-make-freertos-builtin/syscalls.c @@ -0,0 +1,85 @@ +#include + +#include "hal.h" + +int _fstat(int fd, struct stat *st) { + if (fd < 0) return -1; + st->st_mode = S_IFCHR; + return 0; +} + +void *_sbrk(int incr) { + extern char _end; + static unsigned char *heap = NULL; + unsigned char *prev_heap; + if (heap == NULL) heap = (unsigned char *) &_end; + prev_heap = heap; + heap += 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) {} diff --git a/examples/stm32/nucleo-h563zi-make-freertos-builtin/sysinit.c b/examples/stm32/nucleo-h563zi-make-freertos-builtin/sysinit.c new file mode 100644 index 00000000..4d84f947 --- /dev/null +++ b/examples/stm32/nucleo-h563zi-make-freertos-builtin/sysinit.c @@ -0,0 +1,41 @@ +// Copyright (c) 2023 Cesanta Software Limited +// All rights reserved +// +// This file contains essentials required by the CMSIS: +// uint32_t SystemCoreClock - holds the system core clock value +// SystemInit() - initialises the system, e.g. sets up clocks + +#include "hal.h" + +uint32_t SystemCoreClock = CPU_FREQUENCY; + +void SystemInit(void) { // Called automatically by startup code + SCB->CPACR |= ((3UL << 20U) | (3UL << 22U)); // Enable FPU + asm("DSB"); + asm("ISB"); + if (ldo_is_on()) { + PWR->VOSCR = PWR_VOSCR_VOS_0 | PWR_VOSCR_VOS_1; // Select VOS0 + } else { + PWR->VOSCR = PWR_VOSCR_VOS_1; // Select VOS1 + } + uint32_t f = PWR->VOSCR; // fake read to wait for bus clocking + while ((PWR->VOSSR & PWR_VOSSR_ACTVOSRDY) == 0) spin(1); + (void) f; + FLASH->ACR |= FLASH_LATENCY; + RCC->CR = RCC_CR_HSION; // Clear HSI clock divisor + while ((RCC->CR & RCC_CR_HSIRDY) == 0) spin(1); // Wait until done + RCC->CFGR2 = (PPRE3 << 12) | (PPRE2 << 8) | (PPRE1 << 4) | (HPRE << 0); + RCC->PLL1DIVR = + ((PLL1_P - 1) << 9) | ((PLL1_N - 1) << 0); // Set PLL1_P PLL1_N + // Enable P and Q divider outputs; set PLL1_M, select HSI as source, + // !PLL1VCOSEL, PLL1RGE=0 + RCC->PLL1CFGR = + RCC_PLL1CFGR_PLL1QEN | RCC_PLL1CFGR_PLL1PEN | (PLL1_M << 8) | (1 << 0); + RCC->CR |= RCC_CR_PLL1ON; // Enable PLL1 + while ((RCC->CR & RCC_CR_PLL1RDY) == 0) spin(1); // Wait until done + RCC->CFGR1 |= (3 << 0); // Set clock source to PLL1 + while ((RCC->CFGR1 & (7 << 3)) != (3 << 3)) spin(1); // Wait until done + + rng_init(); // Initialise random number generator + SysTick_Config(CPU_FREQUENCY / 1000); // Sys tick every 1ms +}