Merge pull request #2106 from cesanta/standex

Standardize TM4C FreeRTOS
This commit is contained in:
Sergio R. Caprile 2023-03-06 16:01:49 -03:00 committed by GitHub
commit 0de1e6a3af
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
15 changed files with 323 additions and 334 deletions

View File

@ -17,7 +17,6 @@ SECTIONS {
_edata = .; /* for init_ram() */
} > sram AT > flash
_sidata = LOADADDR(.data);
. = ALIGN (CONSTANT (COMMONPAGESIZE));
.bss : {
_sbss = .; /* for init_ram() */

View File

@ -1,9 +1,9 @@
#pragma once
#include "mcu.h"
#include "hal.h"
#define configUSE_PREEMPTION 1
#define configCPU_CLOCK_HZ FREQ
#define configCPU_CLOCK_HZ SYS_FREQUENCY
#define configTICK_RATE_HZ 1000
#define configMAX_PRIORITIES 5
#define configUSE_16_BIT_TICKS 0

View File

@ -1,32 +1,56 @@
ROOT ?= $(realpath $(CURDIR)/../../..)
CFLAGS ?= -W -Wall -Wextra -Werror -Wundef -Wshadow -Wdouble-promotion \
-Wformat-truncation -fno-common -Wconversion \
-g3 -Os -ffunction-sections -fdata-sections \
-mcpu=cortex-m4 -mthumb -mfloat-abi=hard -mfpu=fpv4-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
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_tm4c/Device/TI/TM4C/Include
CFLAGS += -mcpu=cortex-m4 -mthumb -mfloat-abi=hard -mfpu=fpv4-sp-d16
LDFLAGS ?= -Tlink.ld -nostdlib -nostartfiles --specs nano.specs -lc -lgcc -Wl,--gc-sections -Wl,-Map=$@.map
FREERTOS_VERSION ?= V10.5.0
FREERTOS_REPO ?= https://github.com/FreeRTOS/FreeRTOS-Kernel
SOURCES = main.c syscalls.c sysinit.c
SOURCES += startup.c # startup file. Compiler-dependent!
build example: firmware.bin
# FreeRTOS
SOURCES += FreeRTOS-Kernel/portable/MemMang/heap_4.c
SOURCES += FreeRTOS-Kernel/portable/GCC/ARM_CM4F/port.c
CFLAGS += -IFreeRTOS-Kernel/include
CFLAGS += -IFreeRTOS-Kernel/portable/GCC/ARM_CM4F -Wno-conversion
SOURCES += mongoose.c net.c packed_fs.c
CFLAGS += $(CFLAGS_EXTRA) # Mongoose options are defined in mongoose_custom.h
ifeq ($(OS),Windows_NT)
RM = cmd /C del /Q /F /S
else
RM = rm -rf
endif
all build example: firmware.bin
firmware.elf: FreeRTOS-Kernel $(SOURCES)
arm-none-eabi-gcc -o $@ $(SOURCES) $(CFLAGS)\
-IFreeRTOS-Kernel/include \
-IFreeRTOS-Kernel/portable/GCC/ARM_CM4F \
-Wno-conversion \
$(wildcard FreeRTOS-Kernel/*.c) \
FreeRTOS-Kernel/portable/MemMang/heap_4.c \
FreeRTOS-Kernel/portable/GCC/ARM_CM4F/port.c \
$(LDFLAGS)
firmware.bin: firmware.elf
arm-none-eabi-objcopy -O binary $< $@
FreeRTOS-Kernel:
git clone --depth 1 -b $(FREERTOS_VERSION) $(FREERTOS_REPO) $@
firmware.elf: FreeRTOS-Kernel cmsis_core cmsis_tm4c $(SOURCES) hal.h link.ld
arm-none-eabi-gcc $(SOURCES) $(wildcard FreeRTOS-Kernel/*.c) $(CFLAGS) $(LDFLAGS) -o $@
flash: firmware.bin
@echo "This requires Uniflash"
cmsis_core: # ARM CMSIS core headers
git clone --depth 1 -b 5.9.0 https://github.com/ARM-software/CMSIS_5 $@
cmsis_tm4c: # CMSIS headers for TM4C series
git clone --depth 1 --no-checkout https://github.com/speters/CMSIS $@ && cd $@ && git sparse-checkout set Device/TI/TM4C && git checkout
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/1
update: firmware.bin
curl --fail-with-body -su :$(VCON_API_KEY) $(DEVICE_URL)/ota --data-binary @$<
test update: CFLAGS_EXTRA += -DUART_DEBUG=UART1
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
grep 'MQTT connected' /tmp/output.txt # Check for MQTT connection success
clean:
rm -rf firmware.* FreeRTOS-Kernel
$(RM) firmware.* *.su cmsis_core cmsis_tm4c FreeRTOS-Kernel

View File

@ -0,0 +1,175 @@
// Copyright (c) 2022 Cesanta Software Limited
// All rights reserved
// https://www.ti.com/lit/pdf/spms433
#pragma once
#include "TM4C1294NCPDT.h"
#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 << 8) | (num))
#define PINNO(pin) (pin & 255)
#define PINBANK(pin) pinbank(pin >> 8)
// This MCU doesn't have GPIOI nor GPIOO
static inline unsigned int pinbank(unsigned int bank) {
bank = bank > 'O' ? bank - 2 : bank > 'I' ? bank - 1 : bank;
return bank - 'A';
}
// 5.5, Table 5-12: configure flash (and EEPROM) timing in accordance to clock
// freq
enum {
PLL_CLK = 25,
PLL_M = 96,
PLL_N = 5,
PLL_Q = 1,
PSYSDIV = 4
}; // Run at 120 Mhz
#define PLL_FREQ (PLL_CLK * PLL_M / PLL_N / PLL_Q / PSYSDIV)
#define FLASH_CLKHIGH 6
#define FLASH_WAITST 5
#define SYS_FREQUENCY (PLL_FREQ * 1000000)
static inline void spin(volatile uint32_t count) {
while (count--) (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_HIGH };
enum { GPIO_PULL_NONE, GPIO_PULL_UP, GPIO_PULL_DOWN };
#define GPIO(bank) ((GPIOA_AHB_Type *) (GPIOA_AHB_BASE + 0x1000U * (bank)))
// CMSIS header forces 0xFF mask when writing to DATA (see 10.6 in datasheet)
// and does not seem to support that feature for writing by defining RESERVED0
// to read-only
static inline void gpio_toggle(uint16_t pin) {
GPIOA_AHB_Type *gpio = GPIO(PINBANK(pin));
volatile uint32_t *GPIODATA = (volatile uint32_t *) gpio->RESERVED0;
uint8_t mask = BIT(PINNO(pin));
GPIODATA[mask] ^= mask;
}
static inline int gpio_read(uint16_t pin) {
GPIOA_AHB_Type *gpio = GPIO(PINBANK(pin));
volatile uint32_t *GPIODATA = (volatile uint32_t *) gpio->RESERVED0;
uint8_t mask = BIT(PINNO(pin));
return GPIODATA[mask] ? 1 : 0;
}
static inline void gpio_write(uint16_t pin, bool val) {
GPIOA_AHB_Type *gpio = GPIO(PINBANK(pin));
volatile uint32_t *GPIODATA = (volatile uint32_t *) gpio->RESERVED0;
uint8_t mask = BIT(PINNO(pin));
GPIODATA[mask] = val ? mask : 0;
}
static inline void gpio_init(uint16_t pin, uint8_t mode, uint8_t type,
uint8_t speed, uint8_t pull, uint8_t af) {
GPIOA_AHB_Type *gpio = GPIO(PINBANK(pin));
uint8_t n = (uint8_t) (PINNO(pin));
SYSCTL->RCGCGPIO |= BIT(PINBANK(pin)); // Enable GPIO clock
if (mode == GPIO_MODE_ANALOG) {
gpio->AMSEL |= BIT(PINNO(pin));
return;
}
if (mode == GPIO_MODE_INPUT) {
gpio->DIR &= ~BIT(PINNO(pin));
} else if (mode == GPIO_MODE_OUTPUT) {
gpio->DIR |= BIT(PINNO(pin));
} else { // GPIO_MODE_AF
SETBITS(gpio->PCTL, 15UL << ((n & 7) * 4),
((uint32_t) af) << ((n & 7) * 4));
gpio->AFSEL |= BIT(PINNO(pin));
}
gpio->DEN |= BIT(PINNO(pin)); // Enable pin as digital function
if (type == GPIO_OTYPE_OPEN_DRAIN)
gpio->ODR |= BIT(PINNO(pin));
else // GPIO_OTYPE_PUSH_PULL
gpio->ODR &= ~BIT(PINNO(pin));
if (speed == GPIO_SPEED_LOW)
gpio->SLR |= BIT(PINNO(pin));
else // GPIO_SPEED_HIGH
gpio->SLR &= ~BIT(PINNO(pin));
if (pull == GPIO_PULL_UP) {
gpio->PUR |= BIT(PINNO(pin)); // setting one...
} else if (pull == GPIO_PULL_DOWN) {
gpio->PDR |= BIT(PINNO(pin)); // ...just clears the other
} else {
gpio->PUR &= ~BIT(PINNO(pin));
gpio->PDR &= ~BIT(PINNO(pin));
}
}
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);
}
static inline void gpio_irq_attach(uint16_t pin) {
uint8_t irqvecs[] = {16, 17, 18, 19, 20, 30, 31, 32,
51, 52, 53, 72, 73, 76, 84};
GPIOA_AHB_Type *gpio = GPIO(PINBANK(pin));
gpio->IS &= ~BIT(PINNO(pin)); // edge sensitive
gpio->IBE |= BIT(PINNO(pin)); // both edges
gpio->IM |= BIT(PINNO(pin)); // enable pin irq
int irqvec = irqvecs[PINBANK(pin)]; // IRQ vector index, 2.5.2
NVIC_SetPriority(irqvec, 3);
NVIC_EnableIRQ(irqvec);
}
#ifndef UART_DEBUG
#define UART_DEBUG UART0
#endif
#define UART_OFFSET 0x1000
#define UART(N) ((UART0_Type *) (UART0_BASE + UART_OFFSET * (N)))
#define UARTNO(u) ((uint8_t) (((unsigned int) (u) -UART0_BASE) / UART_OFFSET))
static inline void uart_init(UART0_Type *uart, unsigned long baud) {
struct uarthw {
uint16_t rx, tx; // pins
uint8_t af; // Alternate function
};
// rx, tx, af for UART0,1,2
struct uarthw uarthw[3] = {{PIN('A', 0), PIN('A', 1), 1},
{PIN('B', 0), PIN('B', 1), 1},
{PIN('A', 6), PIN('A', 7), 1}}; // or PD4, PD5...
uint8_t uartno = UARTNO(uart);
SYSCTL->RCGCUART |= BIT(uartno); // Enable peripheral clock
gpio_init(uarthw[uartno].tx, GPIO_MODE_AF, GPIO_OTYPE_PUSH_PULL,
GPIO_SPEED_HIGH, 0, uarthw[uartno].af);
gpio_init(uarthw[uartno].rx, GPIO_MODE_AF, GPIO_OTYPE_PUSH_PULL,
GPIO_SPEED_HIGH, 0, uarthw[uartno].af);
// (16.3.2) ClkDiv = 16 (HSE=0)
// BRD = BRDI + BRDF = UARTSysClk / (ClkDiv * Baud Rate)
// UARTFBRD[DIVFRAC] = integer(BRDF * 64 + 0.5)
// must write in this order
uart->CTL = 0; // Disable this UART, clear HSE
uart->IBRD = SYS_FREQUENCY / (16 * baud); // Baud rate, integer part
uart->FBRD = ((SYS_FREQUENCY % (16 * baud)) >> 26) &
0x3F; // Baud rate, fractional part
uart->LCRH = (3 << 5); // 8N1, no FIFOs;
uart->CTL |= BIT(0) | BIT(9) | BIT(8); // Set UARTEN, RXE, TXE
}
static inline void uart_write_byte(UART0_Type *uart, uint8_t byte) {
uart->DR = byte;
while ((uart->FR & BIT(7)) == 0) spin(1);
}
static inline void uart_write_buf(UART0_Type *uart, char *buf, size_t len) {
while (len-- > 0) uart_write_byte(uart, *(uint8_t *) buf++);
}
static inline int uart_read_ready(UART0_Type *uart) {
return uart->FR & BIT(6); // If RXFF bit is set, data is ready
}
static inline uint8_t uart_read_byte(UART0_Type *uart) {
return (uint8_t) (uart->DR & 0xFF);
}

View File

@ -1,13 +1,13 @@
ENTRY(_reset);
ENTRY(Reset_Handler);
MEMORY {
flash(rx) : ORIGIN = 0x00000000, LENGTH = 1024k
flash(rx) : ORIGIN = 0x00000000, LENGTH = 1024k
sram(rwx) : ORIGIN = 0x20000000, LENGTH = 256k
}
_estack = ORIGIN(sram) + LENGTH(sram); /* stack points to end of SRAM */
SECTIONS {
.vectors : { KEEP(*(.vectors)) } > flash
.text : { *(.text*) } > flash
.text : { *(.text* .text.*) } > flash
.rodata : { *(.rodata*) } > flash
.data : {

View File

@ -1,7 +1,7 @@
// Copyright (c) 2022 Cesanta Software Limited
// Copyright (c) 2022-2023 Cesanta Software Limited
// All rights reserved
#include "mcu.h"
#include "hal.h"
#include "mongoose.h"
#define LED1 PIN('N', 1) // On-board LED pin
@ -9,37 +9,33 @@
#define LED3 PIN('F', 4) // On-board LED pin
#define LED4 PIN('F', 0) // On-board LED pin
// 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;
#define LED LED1 // Use this LED for blinking
#define BLINK_PERIOD_MS 1000 // LED blinking period in millis
static void timer_fn(void *arg) {
struct mg_tcpip_if *ifp = arg; // And show
const char *names[] = {"down", "up", "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 ethernet_init(void) {
// See datasheet: https://www.ti.com/lit/pdf/spms433
// Initialise Ethernet. Enable MAC GPIO pins, see
// https://www.ti.com/lit/pdf/spms433
// Assign LED3 and LED4 to the EPHY, "activity" and "link", respectively.
// (20.4.2.4)
gpio_init(LED3, GPIO_MODE_AF, GPIO_OTYPE_PUSH_PULL, GPIO_SPEED_HIGH,
GPIO_PULL_NONE, 5); // EN0LED1
gpio_init(LED4, GPIO_MODE_AF, GPIO_OTYPE_PUSH_PULL, GPIO_SPEED_HIGH,
GPIO_PULL_NONE, 5); // EN0LED0
nvic_enable_irq(40); // Setup Ethernet IRQ handler
NVIC_EnableIRQ(EMAC0_IRQn); // Setup Ethernet IRQ handler
// Initialize Ethernet clocks, see datasheet section 5
// Turn Flash Prefetch off (silicon errata ETH#02)
volatile uint32_t *IMC = (uint32_t *) 0x400FD000;
uint32_t val = IMC[0xFC8 / sizeof(*IMC)];
uint32_t val = FLASH_CTRL->CONF;
val &= ~BIT(17);
val |= BIT(16);
IMC[0xFC8 / sizeof(*IMC)] = val;
FLASH_CTRL->CONF = val;
SYSCTL->RCGCEMAC |= BIT(0); // Enable EMAC clock
SYSCTL->SREMAC |= BIT(0); // Reset EMAC
SYSCTL->SREMAC &= ~BIT(0);
@ -58,44 +54,51 @@ static void server(void *args) {
// Initialise Mongoose network stack
// Specify MAC address, and IP/mask/GW in network byte order for static
// IP configuration. If IP/mask/GW are unset, DHCP is going to be used
MG_INFO(("Initializing Ethernet driver"));
ethernet_init();
struct mg_tcpip_driver_tm4c_data driver_data = {.mdc_cr = 1}; // See driver_tm4c.h
struct mg_tcpip_driver_tm4c_data driver_data = {.mdc_cr = 1};
struct mg_tcpip_if mif = {
.mac = {2, 0, 1, 2, 3, 5},
.driver = &mg_tcpip_driver_tm4c,
.driver_data = &driver_data,
};
mg_tcpip_init(&mgr, &mif);
volatile uint32_t *IMC = (uint32_t *) 0x400FD000;
uint32_t val = IMC[0xFC8 / sizeof(*IMC)]; // Turn Flash Prefetch on again
uint32_t val = FLASH_CTRL->CONF; // Turn Flash Prefetch on again
val &= ~BIT(16);
val |= BIT(17);
IMC[0xFC8 / sizeof(*IMC)] = val;
FLASH_CTRL->CONF = val;
mg_timer_add(&mgr, BLINK_PERIOD_MS, MG_TIMER_REPEAT, timer_fn, &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
MG_INFO(("MAC: %M. Waiting for IP...", mg_print_mac, mif.mac));
while (mif.state != MIP_STATE_READY) {
mg_mgr_poll(&mgr, 0);
}
MG_INFO(("Initialising application..."));
extern void device_dashboard_fn(struct mg_connection *, int, void *, void *);
mg_http_listen(&mgr, "http://0.0.0.0", device_dashboard_fn, NULL);
MG_INFO(("Starting event loop"));
for (;;) mg_mgr_poll(&mgr, 1); // Infinite event loop
(void) args;
}
static void blinker(void *args) {
gpio_init(LED1, GPIO_MODE_OUTPUT, GPIO_OTYPE_PUSH_PULL, GPIO_SPEED_HIGH,
gpio_init(LED, GPIO_MODE_OUTPUT, GPIO_OTYPE_PUSH_PULL, GPIO_SPEED_HIGH,
GPIO_PULL_NONE, 0);
for (;;) {
gpio_toggle(LED1);
vTaskDelay(pdMS_TO_TICKS(750));
(void) args; // MG_INFO(("blink %s, RAM: %u", (char *) args,
// xPortGetFreeHeapSize()));
gpio_toggle(LED);
vTaskDelay(pdMS_TO_TICKS(BLINK_PERIOD_MS));
}
(void) args;
}
int main(void) {
clock_init(); // Set clock to 120MHz
systick_init(FREQ / 1000); // Tick every 1 ms
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;
}

View File

@ -1,261 +0,0 @@
// Copyright (c) 2022 Cesanta Software Limited
// All rights reserved
// https://www.ti.com/lit/pdf/spms433
#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 << 8) | (num))
#define PINNO(pin) (pin & 255)
#define PINBANK(pin) pinbank(pin >> 8)
// This MCU doesn't have GPIOI nor GPIOO
static inline unsigned int pinbank(unsigned int bank) {
bank = bank > 'O' ? bank - 2 : bank > 'I' ? bank - 1 : bank;
return bank - 'A';
}
// 5.5, Table 5-12: configure flash (and EEPROM) timing in accordance to clock
// freq
enum {
PLL_CLK = 25,
PLL_M = 96,
PLL_N = 5,
PLL_Q = 1,
PSYSDIV = 4
}; // Run at 120 Mhz
#define PLL_FREQ (PLL_CLK * PLL_M / PLL_N / PLL_Q / PSYSDIV)
#define FLASH_CLKHIGH 6
#define FLASH_WAITST 5
#define FREQ (PLL_FREQ * 1000000)
static inline void spin(volatile uint32_t count) {
while (count--) asm("nop");
}
struct systick {
volatile uint32_t CTRL, LOAD, VAL, CALIB;
};
#define SYSTICK ((struct systick *) 0xe000e010)
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 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 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)
struct sysctl {
volatile uint32_t DONTCARE0[31], MOSCCTL, RESERVED0[12], RSCLKCFG,
RESERVED1[3], MEMTIM0, DONTCARE1[39], PLLFREQ0, PLLFREQ1, PLLSTAT,
DONTCARE2[241], SREPHY, DONTCARE3[26], SREMAC, DONTCARE4[26], RCGCGPIO,
DONTCARE5[3], RCGCUART, DONTCARE6[5], RCGCEPHY, DONTCARE7[26], RCGCEMAC,
DONTCARE8[228], PREPHY, DONTCARE9[26], PREMAC;
};
#define SYSCTL ((struct sysctl *) 0x400FE000)
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_HIGH };
enum { GPIO_PULL_NONE, GPIO_PULL_UP, GPIO_PULL_DOWN };
// 10.3, 10.6
struct gpio {
volatile uint32_t GPIODATA[256], GPIODIR, GPIOIS, GPIOIBE, GPIOIEV, GPIOIM,
GPIORIS, GPIOMIS, GPIOICR, GPIOAFSEL, RESERVED1[55], GPIODR2R, GPIODR4R,
GPIODR8R, GPIOODR, GPIOPUR, GPIOPDR, GPIOSLR, GPIODEN, GPIOLOCK, GPIOCR,
GPIOAMSEL, GPIOPCTL, GPIOADCCTL, GPIODMACTL, GPIOSI, GPIODR12R,
GPIOWAKEPEN, GPIOWAKELVL, GPIOWAKESTAT, RESERVED2[669], GPIOPP, GPIOPC,
RESERVED3[2], GPIOPeriphID4, GPIOPeriphID5, GPIOPeriphID6, GPIOPeriphID7,
GPIOPeriphID0, GPIOPeriphID1, GPIOPeriphID2, GPIOPeriphID3, GPIOPCellID0,
GPIOPCellID1, GPIOPCellID2, GPIOPCellID3;
};
#define GPIO(N) ((struct gpio *) (0x40058000 + 0x1000 * (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);
uint8_t mask = BIT(PINNO(pin));
gpio->GPIODATA[mask] ^= mask;
}
static inline int gpio_read(uint16_t pin) {
return gpio_bank(pin)->GPIODATA[BIT(PINNO(pin))] ? 1 : 0;
}
static inline void gpio_write(uint16_t pin, bool val) {
struct gpio *gpio = gpio_bank(pin);
uint8_t mask = BIT(PINNO(pin));
gpio->GPIODATA[mask] = val ? mask : 0;
}
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));
SYSCTL->RCGCGPIO |= BIT(PINBANK(pin)); // Enable GPIO clock
if (mode == GPIO_MODE_ANALOG) {
gpio->GPIOAMSEL |= BIT(PINNO(pin));
return;
}
if (mode == GPIO_MODE_INPUT) {
gpio->GPIODIR &= ~BIT(PINNO(pin));
} else if (mode == GPIO_MODE_OUTPUT) {
gpio->GPIODIR |= BIT(PINNO(pin));
} else { // GPIO_MODE_AF
SETBITS(gpio->GPIOPCTL, 15UL << ((n & 7) * 4),
((uint32_t) af) << ((n & 7) * 4));
gpio->GPIOAFSEL |= BIT(PINNO(pin));
}
gpio->GPIODEN |= BIT(PINNO(pin)); // Enable pin as digital function
if (type == GPIO_OTYPE_OPEN_DRAIN)
gpio->GPIOODR |= BIT(PINNO(pin));
else // GPIO_OTYPE_PUSH_PULL
gpio->GPIOODR &= ~BIT(PINNO(pin));
if (speed == GPIO_SPEED_LOW)
gpio->GPIOSLR |= BIT(PINNO(pin));
else // GPIO_SPEED_HIGH
gpio->GPIOSLR &= ~BIT(PINNO(pin));
if (pull == GPIO_PULL_UP) {
gpio->GPIOPUR |= BIT(PINNO(pin)); // setting one...
} else if (pull == GPIO_PULL_DOWN) {
gpio->GPIOPDR |= BIT(PINNO(pin)); // ...just clears the other
} else {
gpio->GPIOPUR &= ~BIT(PINNO(pin));
gpio->GPIOPDR &= ~BIT(PINNO(pin));
}
}
static inline void gpio_input(uint16_t pin) {
gpio_init(pin, GPIO_MODE_INPUT, GPIO_OTYPE_PUSH_PULL, GPIO_SPEED_HIGH,
GPIO_PULL_UP, 0); // EK does not have pull-up resistors
}
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);
}
static inline void gpio_irq_attach(uint16_t pin) {
uint8_t irqvecs[] = {16, 17, 18, 19, 20, 30, 31, 32,
51, 52, 53, 72, 73, 76, 84};
struct gpio *gpio = gpio_bank(pin);
gpio->GPIOIS &= ~BIT(PINNO(pin)); // edge sensitive
gpio->GPIOIBE |= BIT(PINNO(pin)); // both edges
gpio->GPIOIM |= BIT(PINNO(pin)); // enable pin irq
int irqvec = irqvecs[PINBANK(pin)]; // IRQ vector index, 2.5.2
nvic_set_prio(irqvec, 3);
nvic_enable_irq(irqvec);
}
struct uart {
volatile uint32_t UARTDR, UARTRSR, RESERVED0[4], UARTFR, RESERVED1, UARTILPR,
UARTIBRD, UARTFBRD, UARTLCRH, UARTCTL, UARTIFLS, UARTIM, UARTRIS, UARTMIS,
UARTICR, UARTDMACTL, RESERVED2[22], UART9BITADDR, UART9BITAMASK,
RESERVED3[965], UARTPP, RESERVED4, UARTCC, RESERVED5, UARTPeriphID4,
UARTPeriphID5, UARTPeriphID6, UARTPeriphID7, UARTPeriphID0, UARTPeriphID1,
UARTPeriphID2, UARTPeriphID3, UARTPCellID0, UARTPCellID1, UARTPCellID2,
UARTPCellID3;
};
#define UARTECR UARTRSR
#define USART_BASE 0x4000C000
#define USART_OFFSET 0x1000
#define USART(N) ((struct uart *) (USART_BASE + USART_OFFSET * (N)))
#define UARTNO(u) ((uint8_t)(((unsigned int) (u) - USART_BASE) / USART_OFFSET))
#define UART0 USART(0)
#ifndef UART_DEBUG
#define UART_DEBUG UART0
#endif
static inline void uart_init(struct uart *uart, unsigned long baud) {
struct uarthw {
uint16_t rx, tx; // pins
uint8_t af; // Alternate function
};
// af, rx, tx for UART0
struct uarthw uarthw[1] = {{PIN('A', 0), PIN('A', 1), 1}};
if (uart != UART0) return; // uarthw is not populated for other UARTs
uint8_t uartno = UARTNO(uart);
SYSCTL->RCGCUART |= BIT(uartno); // Enable peripheral clock
gpio_init(uarthw[uartno].tx, GPIO_MODE_AF, GPIO_OTYPE_PUSH_PULL,
GPIO_SPEED_HIGH, 0, uarthw[uartno].af);
gpio_init(uarthw[uartno].rx, GPIO_MODE_AF, GPIO_OTYPE_PUSH_PULL,
GPIO_SPEED_HIGH, 0, uarthw[uartno].af);
// (16.3.2) ClkDiv = 16 (HSE=0)
// BRD = BRDI + BRDF = UARTSysClk / (ClkDiv * Baud Rate)
// UARTFBRD[DIVFRAC] = integer(BRDF * 64 + 0.5)
// must write in this order
uart->UARTCTL = 0; // Disable this UART, clear HSE
uart->UARTIBRD = FREQ / (16 * baud); // Baud rate, integer part
uart->UARTFBRD =
((FREQ % (16 * baud)) >> 26) & 0x3F; // Baud rate, fractional part
uart->UARTLCRH = (3 << 5); // 8N1, no FIFOs;
uart->UARTCTL |= BIT(0) | BIT(9) | BIT(8); // Set UARTEN, RXE, TXE
}
static inline void uart_write_byte(struct uart *uart, uint8_t byte) {
uart->UARTDR = byte;
while ((uart->UARTFR & 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->UARTFR & BIT(6); // If RXFF bit is set, data is ready
}
static inline uint8_t uart_read_byte(struct uart *uart) {
return (uint8_t) (uart->UARTDR & 0xFF);
}
static inline void clock_init(void) { // Set clock frequency
SCB->CPACR |= ((3UL << 10 * 2) | (3UL << 11 * 2)); // Enable FPU
asm("DSB");
asm("ISB");
SETBITS(SYSCTL->MOSCCTL, BIT(3) | BIT(2),
BIT(4)); // Enable MOSC circuit (clear NOXTAL and PWRDN, set >10MHz
// range)
SETBITS(SYSCTL->MEMTIM0,
BIT(21) | BIT(5) | 0x1F << 21 | 0xF << 16 | 0x1F << 5 | 0xF << 0,
FLASH_CLKHIGH << 22 | FLASH_WAITST << 16 | FLASH_CLKHIGH << 5 |
FLASH_WAITST << 0); // Configure flash timing (not yet applied)
SETBITS(SYSCTL->RSCLKCFG, 0xF << 24 | (BIT(9) - 1),
3 << 24); // Clear PLL divider, set MOSC as PLL source
SYSCTL->PLLFREQ1 = (PLL_Q - 1) << 8 | (PLL_N - 1)
<< 0; // Set PLL_Q and PLL_N
SYSCTL->PLLFREQ0 =
BIT(23) | PLL_M << 0; // Set PLL_Q, power up PLL (if it were on, we'd
// need to set NEWFREQ in RSCLKCFG instead)
while ((SYSCTL->PLLSTAT & BIT(0)) == 0) spin(1); // Wait for lock
SYSCTL->RSCLKCFG |=
BIT(31) | BIT(28) |
(PSYSDIV - 1) << 0; // Update memory timing, use PLL, set clock divisor
}

View File

@ -0,0 +1 @@
../../../mongoose.c

View File

@ -0,0 +1 @@
../../../mongoose.h

View File

@ -2,7 +2,10 @@
#include <errno.h> // 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_TM4C 1
#define MG_IO_SIZE 256
#define MG_ENABLE_PACKED_FS 1

View File

@ -0,0 +1 @@
../../device-dashboard/net.c

View File

@ -0,0 +1 @@
../../device-dashboard/packed_fs.c

View File

@ -2,22 +2,27 @@
// All rights reserved
// Startup code
__attribute__((naked, noreturn)) void _reset(void) {
__attribute__((naked, noreturn)) void Reset_Handler(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()
// Call the clock system initialization function
extern void SystemInit(void);
SystemInit();
// Call static constructors
extern void __libc_init_array(void);
__libc_init_array();
// Call the application entry point
extern void main(void);
main();
for (;;) (void) 0;
for (;;) (void) 0; // Infinite loop
}
void __attribute__((weak)) DefaultIRQHandler(void) {
for (;;) (void) 0;
}
#define WEAK_ALIAS __attribute__((weak, alias("DefaultIRQHandler")))
WEAK_ALIAS void NMI_Handler(void);
@ -128,11 +133,12 @@ WEAK_ALIAS void I2C7_Handler(void);
WEAK_ALIAS void I2C8_Handler(void);
WEAK_ALIAS void I2C9_Handler(void);
// IRQ table, 2.5.1 Table 2-9
extern void _estack();
// IRQ table
__attribute__((section(".vectors"))) void (*tab[16 + 114])(void) = {
// Cortex interrupts
_estack, _reset, NMI_Handler, HardFault_Handler, MemManage_Handler,
_estack, Reset_Handler, NMI_Handler, HardFault_Handler, MemManage_Handler,
BusFault_Handler, UsageFault_Handler, 0, 0, 0, 0, SVC_Handler,
DebugMon_Handler, 0, PendSV_Handler, SysTick_Handler,

View File

@ -1,6 +1,6 @@
#include <sys/stat.h>
#include "mcu.h"
#include "hal.h"
int _fstat(int fd, struct stat *st) {
if (fd < 0) return -1;

View File

@ -0,0 +1,36 @@
// 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 = SYS_FREQUENCY;
void SystemInit(void) { // Called automatically by startup code
SCB->CPACR |= ((3UL << 10 * 2) | (3UL << 11 * 2)); // Enable FPU
asm("DSB");
asm("ISB");
SETBITS(SYSCTL->MOSCCTL, BIT(3) | BIT(2),
BIT(4)); // Enable MOSC circuit (clear NOXTAL and PWRDN, set >10MHz
// range)
SETBITS(SYSCTL->MEMTIM0,
BIT(21) | BIT(5) | 0x1F << 21 | 0xF << 16 | 0x1F << 5 | 0xF << 0,
FLASH_CLKHIGH << 22 | FLASH_WAITST << 16 | FLASH_CLKHIGH << 5 |
FLASH_WAITST << 0); // Configure flash timing (not yet applied)
SETBITS(SYSCTL->RSCLKCFG, 0xF << 24 | (BIT(9) - 1),
3 << 24); // Clear PLL divider, set MOSC as PLL source
SYSCTL->PLLFREQ1 = (PLL_Q - 1) << 8 | (PLL_N - 1)
<< 0; // Set PLL_Q and PLL_N
SYSCTL->PLLFREQ0 =
BIT(23) | PLL_M << 0; // Set PLL_Q, power up PLL (if it were on, we'd
// need to set NEWFREQ in RSCLKCFG instead)
while ((SYSCTL->PLLSTAT & BIT(0)) == 0) spin(1); // Wait for lock
SYSCTL->RSCLKCFG |=
BIT(31) | BIT(28) |
(PSYSDIV - 1) << 0; // Update memory timing, use PLL, set clock divisor
SysTick_Config(SystemCoreClock / 1000); // Sys tick every 1ms
}