Merge pull request #1882 from cesanta/f746zg-frertos-mip

Add FreeRTOS + MIP example on F746
This commit is contained in:
Sergey Lyubka 2022-11-26 11:57:43 +00:00 committed by GitHub
commit cd218b59f9
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
9 changed files with 667 additions and 0 deletions

View File

@ -0,0 +1,37 @@
#pragma once
#include "mcu.h"
#define configUSE_PREEMPTION 1
#define configCPU_CLOCK_HZ FREQ
#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
#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)
#define vPortSVCHandler SVC_Handler
#define xPortPendSVHandler PendSV_Handler
#define xPortSysTickHandler SysTick_Handler

View File

@ -0,0 +1,36 @@
ROOT ?= $(realpath $(CURDIR)/../../..)
DOCKER ?= docker run --platform linux/amd64 --rm -v $(ROOT):$(ROOT) -w $(CURDIR) mdashnet/armgcc
CFLAGS ?= -W -Wall -Wextra -Werror -Wundef -Wshadow -Wdouble-promotion \
-Wformat-truncation -fno-common -Wconversion \
-g3 -Os -ffunction-sections -fdata-sections \
-mcpu=cortex-m7 -mthumb -mfloat-abi=hard -mfpu=fpv5-sp-d16 \
-I. -I../../../ $(EXTRA_CFLAGS)
LDFLAGS ?= -Tlink.ld -nostartfiles -nostdlib --specs nano.specs -lc -lgcc -Wl,--gc-sections -Wl,-Map=$@.map
SOURCES = main.c boot.c syscalls.c ../../../mongoose.c
FREERTOS_VERSION ?= V10.5.0
FREERTOS_REPO ?= https://github.com/FreeRTOS/FreeRTOS-Kernel
build example: firmware.elf
firmware.elf: FreeRTOS-Kernel $(SOURCES)
$(DOCKER) arm-none-eabi-gcc -o $@ $(SOURCES) $(CFLAGS) \
-IFreeRTOS-Kernel/include \
-IFreeRTOS-Kernel/portable/GCC/ARM_CM7/r0p1 \
-Wno-conversion \
$(wildcard FreeRTOS-Kernel/*.c) \
FreeRTOS-Kernel/portable/MemMang/heap_4.c \
FreeRTOS-Kernel/portable/GCC/ARM_CM7/r0p1/port.c \
$(LDFLAGS)
firmware.bin: firmware.elf
$(DOCKER) arm-none-eabi-objcopy -O binary $< $@
flash: firmware.bin
st-flash --reset write firmware.bin 0x8000000
FreeRTOS-Kernel:
git clone --depth 1 -b $(FREERTOS_VERSION) $(FREERTOS_REPO) $@
clean:
rm -rf firmware.* FreeRTOS-Kernel

View File

@ -0,0 +1,42 @@
# MIP webserver over FreeRTOS on NUCLEO-F746ZG
This firmware uses MIP, an experimental TCP/IP stack of the Mongoose Network Library, running as a FreeRTOS task.
It implements the following:
- Minimal elementary web server, as simple as possible
- No dependencies: no HAL, no CMSIS
- Hand-written [mcu.h](mcu.h) header based on the [datasheet](https://www.st.com/resource/en/reference_manual/rm0385-stm32f75xxx-and-stm32f74xxx-advanced-armbased-32bit-mcus-stmicroelectronics.pdf)
- Interrupt-driven [Ethernet driver](../../../drivers/mip_driver_stm32.c)
- Blue LED blinky, based on another FreeRTOS task
- Debug log on UART3 (st-link)
## Requirements
- [GNU make](http://mongoose.ws/tutorials/tools/#gnu-make)
- [ARM GCC](http://mongoose.ws/tutorials/tools/#arm-gcc)
- [stlink](http://mongoose.ws/tutorials/tools/#stlink) for flashing
The Makefile defaults to using Docker for the compiler, so you don't actually need to install it if you are using a Linux/Mac workstation. If you are not, or you want to run your local ARM compiler, just append `DOCKER=` to the make commands depicted below to call the compiler directly; it must be in your executable path.
In any case, the links above will send you to tutorials on how to install each of those tools in your workstation for Linux, Mac, and Windows.
You'll also need _git_ so the Makefile can clone the FreeRTOS-Kernel repository. We assume you have it since you got to get this repository somehow. If you don't, and don't want to install it, just get the proper [FreeRTOS-Kernel](https://github.com/FreeRTOS/FreeRTOS-Kernel) version (see the Makefile) from its repository, as you did with the Mongoose repository.
## 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 `picocom` at 115200 bps and configure it to insert carriage returns after line feeds:
```sh
$ picocom /dev/ttyACM0 -i -b 115200 --imap=lfcrlf
```
There is also a [detailed tutorial on this example](http://mongoose.ws/tutorials/stm32/nucleo-f746zg-freertos-mip/)
For more details and benchmark data on MIP, check the [baremetal example](../nucleo-f746zg-baremetal/)

View File

@ -0,0 +1,169 @@
// Copyright (c) 2022 Cesanta Software Limited
// All rights reserved
// Startup code
__attribute__((naked, noreturn)) void _reset(void) {
// 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;
}
#define WEAK_ALIAS __attribute__((weak, alias("DefaultIRQHandler")))
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 EXTI0_IRQHandler(void);
WEAK_ALIAS void EXTI1_IRQHandler(void);
WEAK_ALIAS void EXTI2_IRQHandler(void);
WEAK_ALIAS void EXTI3_IRQHandler(void);
WEAK_ALIAS void EXTI4_IRQHandler(void);
WEAK_ALIAS void EXTI9_5_IRQHandler(void);
WEAK_ALIAS void EXTI15_10_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
extern void _estack();
__attribute__((section(".vectors"))) void (*tab[16 + 98])(void) = {
// Cortex interrupts
_estack, _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,84 @@
// Copyright (c) 2022 Cesanta Software Limited
// All rights reserved
#include "mcu.h"
#include "mongoose.h"
// HTTP server event handler function
static void fn(struct mg_connection *c, int ev, void *ev_data, void *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/debug")) {
int level = mg_json_get_long(hm->body, "$.level", MG_LL_DEBUG);
mg_log_set(level);
mg_http_reply(c, 200, "", "Debug level set to %d\n", level);
} else {
mg_http_reply(c, 200, "", "%s\n", "hi");
}
}
(void) fn_data;
}
static void ethernet_init(void) {
// 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
}
static void server(void *args) {
struct mg_mgr mgr; // Initialise Mongoose event manager
mg_mgr_init(&mgr); // and attach it to the MIP interface
mg_log_set(MG_LL_DEBUG); // Set log level
// Initialise Mongoose network stack
// Specify MAC address, either set use_dhcp or enter a static config.
// For static configuration, specify IP/mask/GW in network byte order
MG_INFO(("Initializing Ethernet driver"));
ethernet_init();
struct mip_driver_stm32 driver_data = {.mdc_cr = 4}; // See driver_stm32.h
struct mip_if mif = {
.mac = {2, 0, 1, 2, 3, 5},
.use_dhcp = true,
.driver = &mip_driver_stm32,
.driver_data = &driver_data,
};
mip_init(&mgr, &mif);
MG_INFO(("Starting Mongoose v%s", MG_VERSION)); // Tell the world
mg_http_listen(&mgr, "http://0.0.0.0", fn, &mgr); // Web listener
while (args == NULL) mg_mgr_poll(&mgr, 1000); // Infinite event loop
mg_mgr_free(&mgr); // Unreachable
}
static void blinker(void *args) {
uint16_t led = PIN('B', 7);
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(750));
MG_INFO(("blink %s, RAM: %u", (char *) args, xPortGetFreeHeapSize()));
}
}
int main(void) {
clock_init(); // Set clock to max of 180 MHz
systick_init(FREQ / 1000); // Tick every 1 ms
uart_init(UART3, 115200); // Initialise UART
xTaskCreate(blinker, "blinker", 128, ":)", configMAX_PRIORITIES - 1, NULL);
xTaskCreate(server, "server", 2048, 0, configMAX_PRIORITIES - 1, NULL);
vTaskStartScheduler(); // This blocks
return 0;
}

View File

@ -0,0 +1,218 @@
// 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)
/* System clock
5.3.3: APB1 clock <= 54MHz; APB2 clock <= 108MHz
3.3.2, Table 5: configure flash latency (WS) in accordance to clock freq
38.4: The AHB clock frequency must be at least 25 MHz when the Ethernet controller is used */
enum { APB1_PRE = 5 /* AHB clock / 4 */, APB2_PRE = 4 /* AHB clock / 2 */ };
enum { PLL_HSI = 16, PLL_M = 8, PLL_N = 216, PLL_P = 2 }; // Run at 216 Mhz
//#define PLL_FREQ PLL_HSI
#define PLL_FREQ (PLL_HSI * PLL_N / PLL_M / PLL_P)
#define FLASH_LATENCY 7
#define FREQ (PLL_FREQ * 1000000)
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
}
struct flash {
volatile uint32_t ACR, KEYR, OPTKEYR, SR, CR, AR, RESERVED, OBR, WRPR;
};
#define FLASH ((struct flash *) 0x40023c00)
struct scb {
volatile uint32_t CPUID, ICSR, VTOR, AIRCR, SCR, CCR, SHPR[3], SHCSR, CFSR,
HFSR, DFSR, MMFAR, BFAR, AFSR, ID_PFR[2], ID_DFR, ID_AFR, ID_MFR[4],
ID_ISAR[5], RESERVED0[1], CLIDR, CTR, CCSIDR, CSSELR, CPACR,
RESERVED3[93], STIR, RESERVED4[15], MVFR0, MVFR1, MVFR2, RESERVED5[1],
ICIALLU, RESERVED6[1], ICIMVAU, DCIMVAC, DCISW, DCCMVAU, DCCMVAC, DCCSW,
DCCIMVAC, DCCISW, RESERVED7[6], ITCMCR, DTCMCR, AHBPCR, CACR, AHBSCR,
RESERVED8[1], ABFSR;
};
#define SCB ((struct scb *) 0xe000ed00)
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 APBx prescaler, different from APBx_PRE
// TODO(): make this configurable ?
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 frequency
#if 0
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
SCB->CPACR |= ((3UL << 10 * 2) | (3UL << 11 * 2)); // Enable FPU
asm ("DSB");
asm ("ISB");
FLASH->ACR |= FLASH_LATENCY | BIT(8) | BIT(9); // Flash latency, prefetch
RCC->PLLCFGR &= ~((BIT(17) - 1)); // Clear PLL multipliers
RCC->PLLCFGR |= (((PLL_P - 2) / 2) & 3) << 16; // Set PLL_P
RCC->PLLCFGR |= PLL_M | (PLL_N << 6); // Set PLL_M and PLL_N
RCC->CR |= BIT(24); // Enable PLL
while ((RCC->CR & BIT(25)) == 0) spin(1); // Wait until done
RCC->CFGR = (APB1_PRE << 10) | (APB2_PRE << 13); // Set prescalers
RCC->CFGR |= 2; // Set clock source to PLL
while ((RCC->CFGR & 12) == 0) spin(1); // Wait until done
}

View File

@ -0,0 +1,7 @@
#pragma once
#include <errno.h> // we are not using lwIP
#define MG_ARCH MG_ARCH_FREERTOS
#define MG_ENABLE_MIP 1
#define MG_IO_SIZE 256

View File

@ -0,0 +1,45 @@
#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;
}
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 len;
}
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 _close(int fd) {
(void) fd;
return -1;
}
int _isatty(int fd) {
(void) fd;
return 1;
}
int _read(int fd, char *ptr, int len) {
(void) fd, (void) ptr, (void) len;
return -1;
}
int _lseek(int fd, int ptr, int dir) {
(void) fd, (void) ptr, (void) dir;
return 0;
}