Add nucleo-f746zg-baremetal

This commit is contained in:
Sergey Lyubka 2022-05-26 13:53:36 +01:00
parent 7850b550d8
commit 2ae341cf5e
8 changed files with 736 additions and 1 deletions

View File

@ -78,6 +78,8 @@ jobs:
path: stm32/stm32-nucleo-f429z
- name: stm32-nucleo-h743z
path: stm32/stm32-nucleo-h743z
- name: stm32-nucleo-f746zg-baremetal
path: stm32/nucleo-f746zg-baremetal
- name: nxp-mimxrt1020-azurertos
path: nxp/nxp-mimxrt1020-azurertos
- name: nxp-frdmk66f-freertos
@ -132,4 +134,4 @@ jobs:
steps:
- uses: actions/checkout@v3
- name: ${{ matrix.example.name }}
run: make -C examples/${{ matrix.example.path }} build
run: make -C examples/${{ matrix.example.path }} build

View File

@ -0,0 +1,39 @@
TARGET = firmware
ROOT ?= $(realpath $(CURDIR)/../../..)
DOCKER ?= docker run --rm -v $(ROOT):$(ROOT) -w $(CURDIR) mdashnet/armgcc
CROSS ?= arm-none-eabi
CFLAGS ?= -W -Wall -Wextra -Werror -Wundef -Wshadow -Wdouble-promotion \
-Wformat-truncation -fno-common -Wconversion \
-g3 -Os -ffunction-sections -fdata-sections \
-I. -I$(ROOT) -DMG_ARCH=MG_ARCH_NEWLIB -DMIP_DEBUG=1 \
-DMG_ENABLE_CUSTOM_MILLIS=1 -DMG_ENABLE_LINES=1 -DMG_ENABLE_MIP=1 \
-mcpu=cortex-m7 -mthumb -mfloat-abi=softfp -mfpu=vfpv4 $(EXTRA)
LDFLAGS ?= -Tlink.ld -nostartfiles -nostdlib --specs nano.specs \
-lc -lgcc -Wl,--gc-sections -Wl,-Map=$@.map
SOURCES = boot.c main.c syscalls.c $(ROOT)/drivers/mip_driver_stm32.c \
$(ROOT)/mongoose.c
all build: $(TARGET).bin
$(TARGET).bin: $(TARGET).elf
$(DOCKER) $(CROSS)-objcopy -O binary $< $@
$(TARGET).elf: $(SOURCES) mcu.h
$(DOCKER) $(CROSS)-gcc $(SOURCES) $(CFLAGS) $(LDFLAGS) -o $@
# Build an interactive device dashboard
dash: $(TARGET).elf
dash: CFLAGS += -DDASH -DMG_ENABLE_PACKED_FS=1
dash: SOURCES += $(ROOT)/examples/device-dashboard/packed_fs.c $(ROOT)/examples/device-dashboard/web.c
# Show top 10 stack-hungry functions
su: CFLAGS += -fstack-usage
su: $(TARGET).elf
cat *.su | sort -rnk2 | head -10
# Note: on "unknown chip id" flash error, wire BOOT0 to VDD and st-flash erase
flash: $(TARGET).bin
st-flash --reset write $(TARGET).bin 0x8000000
clean:
@rm -rf $(TARGET).* *.su

View File

@ -0,0 +1,58 @@
# Baremetal webserver on NUCLEO-F746ZG
This firmware uses experimental TCP/IP stack of the Mongoose Network Library,
which implements the following:
- Implements HTTP server and SNTP time synchronisation
- No dependencies: no HAL, no CMSIS, no RTOS
- Hand-written [mcu.h](mcu.h) header based on a [datasheet](https://www.st.com/resource/en/reference_manual/rm0385-stm32f75xxx-and-stm32f74xxx-advanced-armbased-32bit-mcus-stmicroelectronics.pdf)
- Interrupt-driven [mip_driver_stm32.h](../../../drivers/mip_driver_stm32.h) ethernet driver
- Blue LED blinky, based on SysTick interrupt
- User button handler, turns off/on green LED, based on EXTI, interrupt-driven
- Catch-all fault handler that blinks red LED
- Debug log on UART3 (st-link)
## Requirements
- GNU make
- [ARM GCC](https://developer.arm.com/tools-and-software/open-source-software/developer-tools/gnu-toolchain/gnu-rm) toolchain for build
- [st-link](https://github.com/stlink-org/stlink) for flashing
## Usage
Plugin your Nucleo board into USB, and attach an Ethernet cable.
To build and flash:
```sh
make clean flash
```
To see debug log, use any serial monitor program like `cu`:
```sh
cu -l /dev/ttyACM0 -s 115200
```
## Benchmark
A quick comparison is made with several other implementations.
Note: `IP` in the table below is the IP address printed on the console after
boot. The benchmark command is the same: `siege -c 5 -t 5s http://IP`
| | Zephyr | LWIP sockets | LWIP raw | MIP |
| ------------------- | -------- | ------------ | -------- | ---- |
| Requests per second | 3 | 16 | 286 | 1080 |
| Firmware size | 117k (*) | 160k | 114k | 28k |
- Zephyr: uses Zehypr's RTOS and TCP stack, with Mongoose library on top,
[source code](https://github.com/cesanta/mongoose/tree/master/examples/zephyr/http-server).
(*) By default, Zephyr example is TLS-enabled. To compare sizes, a TLS-disabled
build was done by disabling TLS in `prj.conf` and `CMakeLists.txt`
- LWIP sockets: uses FreeRTOS and LWIP with sockets support, with Mongoose
library on top, [source code](https://github.com/mongoose-examples/stm32-nucleo-f746z).
built with `#define MG` in `Core/main.c`
- LWIP raw: uses FreeRTOS and LWIP without sockets, LWIP's httpd server,
[source code](https://github.com/mongoose-examples/stm32-nucleo-f746z).
built with `#define MG` line commented out in `Core/main.c`
- MIP: this repository

View File

@ -0,0 +1,176 @@
// Copyright (c) 2022 Cesanta Software Limited
// All rights reserved
// Startup code
__attribute__((naked, noreturn)) void _reset(void) {
// Init stack
asm("ldr sp, = _estack");
// Initialise memory
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++;
// Call main()
extern void main(void);
main();
for (;;) (void) 0;
}
void __attribute__((weak)) DefaultIRQHandler(void) {
for (;;) (void) 0;
}
void __attribute__((weak)) EXTI_IRQHandler(void) {
for (;;) (void) 0;
}
#define WEAK_ALIAS __attribute__((weak, alias("DefaultIRQHandler")))
__attribute__((alias("EXTI_IRQHandler"))) void EXTI0_IRQHandler(void);
__attribute__((alias("EXTI_IRQHandler"))) void EXTI1_IRQHandler(void);
__attribute__((alias("EXTI_IRQHandler"))) void EXTI2_IRQHandler(void);
__attribute__((alias("EXTI_IRQHandler"))) void EXTI3_IRQHandler(void);
__attribute__((alias("EXTI_IRQHandler"))) void EXTI4_IRQHandler(void);
__attribute__((alias("EXTI_IRQHandler"))) void EXTI9_5_IRQHandler(void);
__attribute__((alias("EXTI_IRQHandler"))) void EXTI15_10_IRQHandler(void);
WEAK_ALIAS void NMI_Handler(void);
WEAK_ALIAS void HardFault_Handler(void);
WEAK_ALIAS void MemManage_Handler(void);
WEAK_ALIAS void BusFault_Handler(void);
WEAK_ALIAS void UsageFault_Handler(void);
WEAK_ALIAS void SVC_Handler(void);
WEAK_ALIAS void DebugMon_Handler(void);
WEAK_ALIAS void PendSV_Handler(void);
WEAK_ALIAS void SysTick_Handler(void);
WEAK_ALIAS void WWDG_IRQHandler(void);
WEAK_ALIAS void PVD_IRQHandler(void);
WEAK_ALIAS void TAMP_STAMP_IRQHandler(void);
WEAK_ALIAS void RTC_WKUP_IRQHandler(void);
WEAK_ALIAS void FLASH_IRQHandler(void);
WEAK_ALIAS void RCC_IRQHandler(void);
WEAK_ALIAS void DMA1_Stream0_IRQHandler(void);
WEAK_ALIAS void DMA1_Stream1_IRQHandler(void);
WEAK_ALIAS void DMA1_Stream2_IRQHandler(void);
WEAK_ALIAS void DMA1_Stream3_IRQHandler(void);
WEAK_ALIAS void DMA1_Stream4_IRQHandler(void);
WEAK_ALIAS void DMA1_Stream5_IRQHandler(void);
WEAK_ALIAS void DMA1_Stream6_IRQHandler(void);
WEAK_ALIAS void ADC_IRQHandler(void);
WEAK_ALIAS void CAN1_TX_IRQHandler(void);
WEAK_ALIAS void CAN1_RX0_IRQHandler(void);
WEAK_ALIAS void CAN1_RX1_IRQHandler(void);
WEAK_ALIAS void CAN1_SCE_IRQHandler(void);
WEAK_ALIAS void TIM1_BRK_TIM9_IRQHandler(void);
WEAK_ALIAS void TIM1_UP_TIM10_IRQHandler(void);
WEAK_ALIAS void TIM1_TRG_COM_TIM11_IRQHandler(void);
WEAK_ALIAS void TIM1_CC_IRQHandler(void);
WEAK_ALIAS void TIM2_IRQHandler(void);
WEAK_ALIAS void TIM3_IRQHandler(void);
WEAK_ALIAS void TIM4_IRQHandler(void);
WEAK_ALIAS void I2C1_EV_IRQHandler(void);
WEAK_ALIAS void I2C1_ER_IRQHandler(void);
WEAK_ALIAS void I2C2_EV_IRQHandler(void);
WEAK_ALIAS void I2C2_ER_IRQHandler(void);
WEAK_ALIAS void SPI1_IRQHandler(void);
WEAK_ALIAS void SPI2_IRQHandler(void);
WEAK_ALIAS void USART1_IRQHandler(void);
WEAK_ALIAS void USART2_IRQHandler(void);
WEAK_ALIAS void USART3_IRQHandler(void);
WEAK_ALIAS void RTC_Alarm_IRQHandler(void);
WEAK_ALIAS void OTG_FS_WKUP_IRQHandler(void);
WEAK_ALIAS void TIM8_BRK_TIM12_IRQHandler(void);
WEAK_ALIAS void TIM8_UP_TIM13_IRQHandler(void);
WEAK_ALIAS void TIM8_TRG_COM_TIM14_IRQHandler(void);
WEAK_ALIAS void TIM8_CC_IRQHandler(void);
WEAK_ALIAS void DMA1_Stream7_IRQHandler(void);
WEAK_ALIAS void FMC_IRQHandler(void);
WEAK_ALIAS void SDMMC1_IRQHandler(void);
WEAK_ALIAS void TIM5_IRQHandler(void);
WEAK_ALIAS void SPI3_IRQHandler(void);
WEAK_ALIAS void UART4_IRQHandler(void);
WEAK_ALIAS void UART5_IRQHandler(void);
WEAK_ALIAS void TIM6_DAC_IRQHandler(void);
WEAK_ALIAS void TIM7_IRQHandler(void);
WEAK_ALIAS void DMA2_Stream0_IRQHandler(void);
WEAK_ALIAS void DMA2_Stream1_IRQHandler(void);
WEAK_ALIAS void DMA2_Stream2_IRQHandler(void);
WEAK_ALIAS void DMA2_Stream3_IRQHandler(void);
WEAK_ALIAS void DMA2_Stream4_IRQHandler(void);
WEAK_ALIAS void ETH_IRQHandler(void);
WEAK_ALIAS void ETH_WKUP_IRQHandler(void);
WEAK_ALIAS void CAN2_TX_IRQHandler(void);
WEAK_ALIAS void CAN2_RX0_IRQHandler(void);
WEAK_ALIAS void CAN2_RX1_IRQHandler(void);
WEAK_ALIAS void CAN2_SCE_IRQHandler(void);
WEAK_ALIAS void OTG_FS_IRQHandler(void);
WEAK_ALIAS void DMA2_Stream5_IRQHandler(void);
WEAK_ALIAS void DMA2_Stream6_IRQHandler(void);
WEAK_ALIAS void DMA2_Stream7_IRQHandler(void);
WEAK_ALIAS void USART6_IRQHandler(void);
WEAK_ALIAS void I2C3_EV_IRQHandler(void);
WEAK_ALIAS void I2C3_ER_IRQHandler(void);
WEAK_ALIAS void OTG_HS_EP1_OUT_IRQHandler(void);
WEAK_ALIAS void OTG_HS_EP1_IN_IRQHandler(void);
WEAK_ALIAS void OTG_HS_WKUP_IRQHandler(void);
WEAK_ALIAS void OTG_HS_IRQHandler(void);
WEAK_ALIAS void DCMI_IRQHandler(void);
WEAK_ALIAS void RNG_IRQHandler(void);
WEAK_ALIAS void FPU_IRQHandler(void);
WEAK_ALIAS void UART7_IRQHandler(void);
WEAK_ALIAS void UART8_IRQHandler(void);
WEAK_ALIAS void SPI4_IRQHandler(void);
WEAK_ALIAS void SPI5_IRQHandler(void);
WEAK_ALIAS void SPI6_IRQHandler(void);
WEAK_ALIAS void SAI1_IRQHandler(void);
WEAK_ALIAS void LTDC_IRQHandler(void);
WEAK_ALIAS void LTDC_ER_IRQHandler(void);
WEAK_ALIAS void DMA2D_IRQHandler(void);
WEAK_ALIAS void SAI2_IRQHandler(void);
WEAK_ALIAS void QUADSPI_IRQHandler(void);
WEAK_ALIAS void LPTIM1_IRQHandler(void);
WEAK_ALIAS void CEC_IRQHandler(void);
WEAK_ALIAS void I2C4_EV_IRQHandler(void);
WEAK_ALIAS void I2C4_ER_IRQHandler(void);
WEAK_ALIAS void SPDIF_RX_IRQHandler(void);
// IRQ table
__attribute__((section(".vectors"))) void (*tab[16 + 98])(void) = {
// Cortex interrupts
0, _reset, NMI_Handler, HardFault_Handler, MemManage_Handler,
BusFault_Handler, UsageFault_Handler, 0, 0, 0, 0, SVC_Handler,
DebugMon_Handler, 0, PendSV_Handler, SysTick_Handler,
// Interrupts from peripherals
WWDG_IRQHandler, PVD_IRQHandler, TAMP_STAMP_IRQHandler, RTC_WKUP_IRQHandler,
FLASH_IRQHandler, RCC_IRQHandler, EXTI0_IRQHandler, EXTI1_IRQHandler,
EXTI2_IRQHandler, EXTI3_IRQHandler, EXTI4_IRQHandler,
DMA1_Stream0_IRQHandler, DMA1_Stream1_IRQHandler, DMA1_Stream2_IRQHandler,
DMA1_Stream3_IRQHandler, DMA1_Stream4_IRQHandler, DMA1_Stream5_IRQHandler,
DMA1_Stream6_IRQHandler, ADC_IRQHandler, CAN1_TX_IRQHandler,
CAN1_RX0_IRQHandler, CAN1_RX1_IRQHandler, CAN1_SCE_IRQHandler,
EXTI9_5_IRQHandler, TIM1_BRK_TIM9_IRQHandler, TIM1_UP_TIM10_IRQHandler,
TIM1_TRG_COM_TIM11_IRQHandler, TIM1_CC_IRQHandler, TIM2_IRQHandler,
TIM3_IRQHandler, TIM4_IRQHandler, I2C1_EV_IRQHandler, I2C1_ER_IRQHandler,
I2C2_EV_IRQHandler, I2C2_ER_IRQHandler, SPI1_IRQHandler, SPI2_IRQHandler,
USART1_IRQHandler, USART2_IRQHandler, USART3_IRQHandler,
EXTI15_10_IRQHandler, RTC_Alarm_IRQHandler, OTG_FS_WKUP_IRQHandler,
TIM8_BRK_TIM12_IRQHandler, TIM8_UP_TIM13_IRQHandler,
TIM8_TRG_COM_TIM14_IRQHandler, TIM8_CC_IRQHandler, DMA1_Stream7_IRQHandler,
FMC_IRQHandler, SDMMC1_IRQHandler, TIM5_IRQHandler, SPI3_IRQHandler,
UART4_IRQHandler, UART5_IRQHandler, TIM6_DAC_IRQHandler, TIM7_IRQHandler,
DMA2_Stream0_IRQHandler, DMA2_Stream1_IRQHandler, DMA2_Stream2_IRQHandler,
DMA2_Stream3_IRQHandler, DMA2_Stream4_IRQHandler, ETH_IRQHandler,
ETH_WKUP_IRQHandler, CAN2_TX_IRQHandler, CAN2_RX0_IRQHandler,
CAN2_RX1_IRQHandler, CAN2_SCE_IRQHandler, OTG_FS_IRQHandler,
DMA2_Stream5_IRQHandler, DMA2_Stream6_IRQHandler, DMA2_Stream7_IRQHandler,
USART6_IRQHandler, I2C3_EV_IRQHandler, I2C3_ER_IRQHandler,
OTG_HS_EP1_OUT_IRQHandler, OTG_HS_EP1_IN_IRQHandler, OTG_HS_WKUP_IRQHandler,
OTG_HS_IRQHandler, DCMI_IRQHandler, 0, RNG_IRQHandler, FPU_IRQHandler,
UART7_IRQHandler, UART8_IRQHandler, SPI4_IRQHandler, SPI5_IRQHandler,
SPI6_IRQHandler, SAI1_IRQHandler, LTDC_IRQHandler, LTDC_ER_IRQHandler,
DMA2D_IRQHandler, SAI2_IRQHandler, QUADSPI_IRQHandler, LPTIM1_IRQHandler,
CEC_IRQHandler, I2C4_EV_IRQHandler, I2C4_ER_IRQHandler,
SPDIF_RX_IRQHandler};

View File

@ -0,0 +1,29 @@
ENTRY(_reset);
MEMORY {
flash(rx) : ORIGIN = 0x08000000, LENGTH = 1024k
sram(rwx) : ORIGIN = 0x20000000, LENGTH = 320k
}
_estack = ORIGIN(sram) + LENGTH(sram); /* stack points to end of SRAM */
SECTIONS {
.vectors : { KEEP(*(.vectors)) } > flash
.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() */
}

View File

@ -0,0 +1,155 @@
// Copyright (c) 2022 Cesanta Software Limited
// All rights reserved
#include "mcu.h"
#include "drivers/mip_driver_stm32.h"
#include "mongoose.h"
#define LED1 PIN('B', 0) // On-board LED pin (green)
#define LED2 PIN('B', 7) // On-board LED pin (blue)
#define LED3 PIN('B', 14) // On-board LED pin (red)
#define BTN1 PIN('C', 13) // On-board user button
static uint64_t s_ticks, s_exti; // Counters, increased by IRQ handlers
static time_t s_boot_timestamp = 0; // Updated by SNTP
static struct mg_connection *s_sntp_conn = NULL; // SNTP connection
// We have no valid system time(), and we need it for TLS. Implement it
time_t time(time_t *tp) {
time_t t = s_boot_timestamp + (time_t) (mg_millis() / 1000);
if (tp != NULL) *tp = t;
return t;
}
// SNTP connection event handler. When we get a response from an SNTP server,
// adjust s_boot_timestamp. We'll get a valid time from that point on
static void sfn(struct mg_connection *c, int ev, void *ev_data, void *fn_data) {
if (ev == MG_EV_SNTP_TIME) {
uint64_t t = *(uint64_t *) ev_data;
MG_INFO(("%lu SNTP: %lld ms from epoch", c->id, t));
s_boot_timestamp = (time_t) ((t - mg_millis()) / 1000);
} else if (ev == MG_EV_CLOSE) {
s_sntp_conn = NULL;
}
(void) fn_data;
}
static void sntp_cb(void *param) { // SNTP timer function. Sync up time
struct mg_mgr *mgr = (struct mg_mgr *) param;
if (s_sntp_conn == NULL) s_sntp_conn = mg_sntp_connect(mgr, NULL, sfn, NULL);
if (s_boot_timestamp < 9999) mg_sntp_request(s_sntp_conn);
}
static void blink_cb(void *arg) { // Blink periodically
// MG_INFO(("ticks: %u", (unsigned) s_ticks));
gpio_toggle(LED2);
(void) arg;
}
// Server event handler
static void fn(struct mg_connection *c, int ev, void *ev_data, void *fn_data) {
if (ev == MG_EV_POLL) return;
// MG_DEBUG(("%lu %p %d %p %p", c->id, c, ev, ev_data, fn_data));
if (ev == MG_EV_HTTP_MSG) {
struct mg_http_message *hm = (struct mg_http_message *) ev_data;
if (mg_http_match_uri(hm, "/api/stats")) {
// Print some statistics about currently established connections
mg_printf(c, "HTTP/1.1 200 OK\r\nTransfer-Encoding: chunked\r\n\r\n");
mg_http_printf_chunk(c, "ID PROTO TYPE LOCAL REMOTE\n");
for (struct mg_connection *t = c->mgr->conns; t != NULL; t = t->next) {
char loc[40], rem[40];
mg_http_printf_chunk(c, "%-3lu %4s %s %-15s %s\n", t->id,
t->is_udp ? "UDP" : "TCP",
t->is_listening ? "LISTENING"
: t->is_accepted ? "ACCEPTED "
: "CONNECTED",
mg_straddr(&t->loc, loc, sizeof(loc)),
mg_straddr(&t->rem, rem, sizeof(rem)));
}
mg_http_printf_chunk(c, ""); // Don't forget the last empty chunk
} else {
mg_http_reply(c, 200, "", "hi\n");
#if 0
struct mg_http_serve_opts opts = {0};
opts.root_dir = "/web_root";
opts.fs = &mg_fs_packed;
mg_http_serve_dir(c, hm, &opts);
#endif
}
}
(void) fn_data;
}
uint64_t mg_millis(void) { // Declare our own uptime function
return s_ticks; // Return number of milliseconds since boot
}
void DefaultIRQHandler(void) { // Catch-all fault handler
gpio_output(LED3); // Setup red LED
for (;;) spin(2999999), gpio_toggle(LED3); // Blink LED infinitely
}
void SysTick_Handler(void) { // SyStick IRQ handler, triggered every 1ms
s_ticks++;
}
void EXTI_IRQHandler(void) {
s_exti++;
if (EXTI->PR & BIT(PINNO(BTN1))) EXTI->PR = BIT(PINNO(BTN1));
gpio_write(LED1, gpio_read(BTN1)); // No debounce. Turn LED if button pressed
}
int main(void) {
static struct uart *uart = UART3; // Use UART3 - its attached to debug
clock_init(); // Set clock to 216MHz
systick_init(FREQ / 1000); // Increment s_ticks every ms
gpio_output(LED1); // Setup green LED
gpio_output(LED2); // Setup blue LED
gpio_input(BTN1); // Set button to input
irq_exti_attach(BTN1); // Attach BTN1 to exti
uart_init(uart, 115200); // It is wired to the debug port
// Initialise Ethernet. Enable MAC GPIO pins, see
// https://www.farnell.com/datasheets/2014265.pdf section 6.10
uint16_t pins[] = {PIN('A', 1), PIN('A', 2), PIN('A', 7),
PIN('B', 13), 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);
}
nvic_enable_irq(61); // Setup Ethernet IRQ handler
RCC->APB2ENR |= BIT(14); // Enable SYSCFG
SYSCFG->PMC |= BIT(23); // Use RMII. Goes first!
RCC->AHB1ENR |= BIT(25) | BIT(26) | BIT(27); // Enable Ethernet clocks
RCC->AHB1RSTR |= BIT(25); // ETHMAC force reset
RCC->AHB1RSTR &= ~BIT(25); // ETHMAC release reset
struct mg_mgr mgr; // Initialise Mongoose event manager
mg_mgr_init(&mgr); // and attach it to the MIP interface
mg_log_set("2");
mg_timer_add(&mgr, 1000, MG_TIMER_REPEAT, blink_cb, &mgr);
mg_timer_add(&mgr, 5000, MG_TIMER_REPEAT, sntp_cb, &mgr);
mg_http_listen(&mgr, "http://0.0.0.0:80", fn, NULL);
// Initialise Mongoose network stack
// Specify MAC address, and use 0 for IP, mask, GW - i.e. use DHCP
// For static configuration, specify IP/mask/GW in network byte order
struct mip_ipcfg ipcfg = {
.mac = {0xaa, 0xbb, 0xcc, 1, 2, 3}, .ip = 0, .mask = 0, .gw = 0};
struct mip_driver stm32_driver = {.init = mip_driver_stm32_init,
.tx = mip_driver_stm32_tx,
.rxcb = mip_driver_stm32_setrx,
.status = mip_driver_stm32_status};
mip_init(&mgr, &ipcfg, &stm32_driver);
MG_INFO(("Init done, starting main loop"));
#if defined(DASH)
extern void device_dashboard_fn(struct mg_connection *, int, void *, void *);
mg_http_listen(&mgr, "http://0.0.0.0:8000", device_dashboard_fn, &mgr);
#endif
for (;;) mg_mgr_poll(&mgr, 0); // Infinite event loop
return 0;
}

View File

@ -0,0 +1,193 @@
// Copyright (c) 2022 Cesanta Software Limited
// All rights reserved
// https://www.st.com/resource/en/reference_manual/dm00124865-stm32f75xxx-and-stm32f74xxx-advanced-arm-based-32-bit-mcus-stmicroelectronics.pdf
#pragma once
#include <stdbool.h>
#include <stdint.h>
#include <stdio.h>
#include <string.h>
#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 FREQ 16000000
#define FREQ 216000000
static inline void spin(volatile uint32_t count) {
while (count--) asm("nop");
}
struct rcc {
volatile uint32_t CR, PLLCFGR, CFGR, CIR, AHB1RSTR, AHB2RSTR, AHB3RSTR,
RESERVED0, APB1RSTR, APB2RSTR, RESERVED1[2], AHB1ENR, AHB2ENR, AHB3ENR,
RESERVED2, APB1ENR, APB2ENR, RESERVED3[2], AHB1LPENR, AHB2LPENR,
AHB3LPENR, RESERVED4, APB1LPENR, APB2LPENR, RESERVED5[2], BDCR, CSR,
RESERVED6[2], SSCGR, PLLI2SCFGR, PLLSAICFGR, DCKCFGR1, DCKCFGR2;
};
#define RCC ((struct rcc *) 0x40023800)
struct pwr {
volatile uint32_t CR1, CSR1, CR2, CSR2;
};
#define PWR ((struct pwr *) 0x40007000)
struct nvic {
volatile uint32_t ISER[8], RESERVED0[24], ICER[8], RSERVED1[24], ISPR[8],
RESERVED2[24], ICPR[8], RESERVED3[24], IABR[8], RESERVED4[56], IP[240],
RESERVED5[644], STIR;
};
#define NVIC ((struct nvic *) 0xe000e100)
static inline void nvic_set_prio(int irq, uint32_t prio) {
NVIC->IP[irq] = prio << 4;
}
static inline void nvic_enable_irq(int irq) {
NVIC->ISER[irq >> 5] = (uint32_t) (1 << (irq & 31));
}
struct systick {
volatile uint32_t CTRL, LOAD, VAL, CALIB;
};
#define SYSTICK ((struct systick *) 0xe000e010) // 2.2.2
static inline void systick_init(uint32_t ticks) {
if ((ticks - 1) > 0xffffff) return; // Systick timer is 24 bit
SYSTICK->LOAD = ticks - 1;
SYSTICK->VAL = 0;
SYSTICK->CTRL = BIT(0) | BIT(1) | BIT(2); // Enable systick
RCC->APB2ENR |= BIT(14); // Enable SYSCFG
}
struct flash {
volatile uint32_t ACR, KEYR, OPTKEYR, SR, CR, AR, RESERVED, OBR, WRPR;
};
#define FLASH ((struct flash *) 0x40023c00)
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 };
struct gpio {
volatile uint32_t MODER, OTYPER, OSPEEDR, PUPDR, IDR, ODR, BSRR, LCKR, AFR[2];
};
#define GPIO(N) ((struct gpio *) (0x40020000 + 0x400 * (N)))
static struct gpio *gpio_bank(uint16_t pin) {
return GPIO(PINBANK(pin));
}
static inline void gpio_toggle(uint16_t pin) {
struct gpio *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) {
struct gpio *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) {
struct gpio *gpio = gpio_bank(pin);
uint8_t n = (uint8_t) (PINNO(pin));
RCC->AHB1ENR |= 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);
}
struct syscfg {
volatile uint32_t MEMRMP, PMC, EXTICR[4], RESERVED[2], CMPCR;
};
#define SYSCFG ((struct syscfg *) 0x40013800)
struct exti {
volatile uint32_t IMR, EMR, RTSR, FTSR, SWIER, PR;
};
#define EXTI ((struct exti *) 0x40013c00)
static inline void irq_exti_attach(uint16_t pin) {
uint8_t bank = (uint8_t) (PINBANK(pin)), n = (uint8_t) (PINNO(pin));
RCC->APB2ENR |= BIT(14); // Enable SYSCFG
SYSCFG->EXTICR[n / 4] &= ~(15UL << ((n % 4) * 4));
SYSCFG->EXTICR[n / 4] |= (uint32_t) (bank << ((n % 4) * 4));
EXTI->IMR |= BIT(n);
EXTI->RTSR |= BIT(n);
EXTI->FTSR |= BIT(n);
int irqvec = n < 5 ? 6 + n : n < 10 ? 23 : 40; // IRQ vector index, 10.1.2
nvic_set_prio(irqvec, 3);
nvic_enable_irq(irqvec);
}
struct uart {
volatile uint32_t CR1, CR2, CR3, BRR, GTPR, RTOR, RQR, ISR, ICR, RDR, TDR;
};
#define UART1 ((struct uart *) 0x40011000)
#define UART2 ((struct uart *) 0x40004400)
#define UART3 ((struct uart *) 0x40004800)
static inline void uart_init(struct uart *uart, unsigned long baud) {
// https://www.st.com/resource/en/datasheet/stm32f746zg.pdf
uint8_t af = 0; // Alternate function
uint16_t rx = 0, tx = 0; // pins
if (uart == UART1) RCC->APB2ENR |= BIT(4);
if (uart == UART2) RCC->APB1ENR |= BIT(17);
if (uart == UART3) RCC->APB1ENR |= BIT(18);
if (uart == UART1) af = 4, tx = PIN('A', 9), rx = PIN('A', 10);
if (uart == UART2) af = 4, tx = PIN('A', 2), rx = PIN('A', 3);
if (uart == UART3) af = 7, tx = PIN('D', 8), rx = PIN('D', 9);
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 this UART
uart->BRR = FREQ / 4 / baud; // Baud rate. /4 is a PLL prescaler
uart->CR1 |= BIT(0) | BIT(2) | BIT(3); // Set UE, RE, TE
}
static inline void uart_write_byte(struct uart *uart, uint8_t byte) {
uart->TDR = byte;
while ((uart->ISR & BIT(7)) == 0) spin(1);
}
static inline void uart_write_buf(struct uart *uart, char *buf, size_t len) {
while (len-- > 0) uart_write_byte(uart, *(uint8_t *) buf++);
}
static inline int uart_read_ready(struct uart *uart) {
return uart->ISR & BIT(5); // If RXNE bit is set, data is ready
}
static inline uint8_t uart_read_byte(struct uart *uart) {
return (uint8_t) (uart->RDR & 255);
}
static inline void clock_init(void) { // Set clock to 216Mhz
#if 1
RCC->APB1ENR |= BIT(28); // Power enable
PWR->CR1 |= 3UL << 14; // Voltage regulator scale 3
PWR->CR1 |= BIT(16); // Enable overdrive
while ((PWR->CSR1 & BIT(16)) == 0) spin(1); // Wait until done
PWR->CR1 |= BIT(17); // Enable overdrive switching
while ((PWR->CSR1 & BIT(17)) == 0) spin(1); // Wait until done
#endif
FLASH->ACR |= 7 | BIT(8) | BIT(9); // Flash latency 7, prefetch
RCC->PLLCFGR &= ~((BIT(15) - 1)); // PLL = HSI * N / M / P
RCC->PLLCFGR |= 8UL | (216UL << 6); // M = 8, N = 216, P = 2. 216Mhz
RCC->CR |= BIT(24); // Enable PLL
while ((RCC->CR & BIT(25)) == 0) spin(1); // Wait until done
RCC->CFGR = 2 | (5UL << 10) | (4UL << 13); // Set prescalers and PLL clock
while ((RCC->CFGR & 12) == 0) spin(1); // Wait until done
}

View File

@ -0,0 +1,83 @@
#include <sys/stat.h>
#include "mcu.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(UART3, 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;
}