mirror of
https://github.com/cesanta/mongoose.git
synced 2025-01-14 17:58:11 +08:00
Blinky works
This commit is contained in:
parent
d6852f5e74
commit
c44549bfa5
@ -2,44 +2,58 @@
|
||||
PROG = firmware
|
||||
ARCH ?= stm32f1
|
||||
ROOT = $(realpath $(CURDIR)/../..)
|
||||
ENV ?= docker run -it --rm -v $(ROOT):$(ROOT) -w $(CURDIR) mdashnet/armgcc
|
||||
MFLAGS = -DMG_ENABLE_LINES=1 -DMG_ARCH=MG_ARCH_FREERTOS_TCP -DMG_ENABLE_FS=0
|
||||
DOCKER ?= docker run -it --rm -v $(ROOT):$(ROOT) -w $(CURDIR) mdashnet/armgcc
|
||||
MONGOOSE_OPTS = -DMG_ENABLE_LINES=1 -DMG_ARCH=MG_ARCH_FREERTOS_TCP -DMG_ENABLE_FS=0
|
||||
ifeq "$(ARCH)" "stm32f1"
|
||||
MCU = -mcpu=cortex-m3 -mthumb -mfloat-abi=soft
|
||||
else ifeq "$(ARCH)" "stm32f7"
|
||||
MCU = -mcpu=cortex-m7 -mthumb -mfpu=fpv5-sp-d16 -mfloat-abi=hard
|
||||
endif
|
||||
INCS = -I$(ARCH) -I. -I../.. -Ifreertos-kernel/include -Ifreertos-tcp/include -Ifreertos-tcp/portable/Compiler/GCC
|
||||
CFLAGS = -W -Wall -Og $(MCU) -fdata-sections -ffunction-sections $(INCS) $(MFLAGS) $(EXTRA)
|
||||
AFLAGS = --warn --fatal-warnings $(MCU)
|
||||
LDFLAGS = $(MCU) -specs=nano.specs -T$(ARCH)/link.ld -nostartfiles -nostdlib -lc -lm -lnosys -lgcc #-Wl,-Map=obj/$(PROG).map,--cref -Wl,--gc-sections
|
||||
A_SRC = $(ARCH)/boot.s
|
||||
C_SRC = main.c # $(wildcard freertos-tcp/*.c)
|
||||
C_SRC += freertos-kernel/portable/MemMang/heap_4.c $(ARCH)/port.c
|
||||
C_SRC += freertos-kernel/list.c freertos-kernel/tasks.c freertos-kernel/queue.c
|
||||
OBJS := $(C_SRC:%.c=obj/%.o) $(A_SRC:%.s=obj/%.o) #obj/mongoose.o
|
||||
CFLAGS = -W -Wall -Os -g $(MCU) -fdata-sections -ffunction-sections $(INCS) $(MONGOOSE_OPTS) $(EXTRA)
|
||||
LDFLAGS = $(MCU) -specs=nano.specs -Tobj/link.ld -nostartfiles -nostdlib -lc -lm -lnosys -lgcc #-Wl,-Map=obj/$(PROG).map,--cref -Wl,--gc-sections
|
||||
SRCS = main.c # $(wildcard freertos-tcp/*.c)
|
||||
# SRCS += freertos-kernel/portable/MemMang/heap_4.c $(ARCH)/port.c
|
||||
# SRCS += freertos-kernel/list.c freertos-kernel/tasks.c freertos-kernel/queue.c
|
||||
OBJS = obj/boot.o $(SRCS:%.c=obj/%.o) #obj/mongoose.o # ORDER MATTERS - boot (vector table) first!
|
||||
|
||||
all: $(PROG).hex
|
||||
|
||||
$(PROG).bin: $(PROG).elf
|
||||
$(ENV) arm-none-eabi-objcopy -O binary $< $@
|
||||
$(DOCKER) arm-none-eabi-objcopy -O binary $< $@
|
||||
|
||||
$(PROG).hex: $(PROG).bin
|
||||
$(ENV) arm-none-eabi-objcopy -I binary -O ihex --change-address 0x8000000 $< $@
|
||||
$(DOCKER) arm-none-eabi-objcopy -I binary -O ihex --change-address 0x8000000 $< $@
|
||||
|
||||
$(PROG).elf: $(OBJS)
|
||||
$(ENV) arm-none-eabi-gcc $^ $(LDFLAGS) -o $@
|
||||
obj/link.ld: $(ARCH)/link.ld
|
||||
$(DOCKER) arm-none-eabi-cpp -P -imacros $(ARCH)/device.h $< > $@
|
||||
|
||||
$(PROG).elf: $(OBJS) obj/link.ld
|
||||
$(DOCKER) arm-none-eabi-gcc $(OBJS) $(LDFLAGS) -o $@
|
||||
|
||||
obj/%.o: %.c
|
||||
@mkdir -p $(dir $@)
|
||||
$(ENV) arm-none-eabi-gcc $(CFLAGS) -c $< -o $@
|
||||
$(DOCKER) arm-none-eabi-gcc $(CFLAGS) -c $< -o $@
|
||||
|
||||
obj/%.o: %.s
|
||||
obj/boot.o:
|
||||
@mkdir -p $(dir $@)
|
||||
$(ENV) arm-none-eabi-as $(AFLAGS) $< -o $@
|
||||
$(DOCKER) arm-none-eabi-as --warn --fatal-warnings $(MCU) $(ARCH)/boot.s -o $@
|
||||
|
||||
obj/mongoose.o:
|
||||
$(ENV) arm-none-eabi-gcc $(CFLAGS) -c ../../mongoose.c -o $@
|
||||
$(DOCKER) arm-none-eabi-gcc $(CFLAGS) -c ../../mongoose.c -o $@
|
||||
|
||||
flash: $(PROG).bin
|
||||
st-flash write $< 0x8000000
|
||||
|
||||
gdb: $(PROG).elf
|
||||
arm-none-eabi-gdb \
|
||||
-ex 'set confirm off' \
|
||||
-ex 'target extended-remote :4242' \
|
||||
-ex 'monitor reset halt' \
|
||||
-ex 'monitor reset init' \
|
||||
-ex 'b main' \
|
||||
-ex 'r' \
|
||||
$<
|
||||
|
||||
clean:
|
||||
@rm -rf *.{bin,elf,map,lst,tgz,zip,hex} obj
|
3
examples/stm32/README.md
Normal file
3
examples/stm32/README.md
Normal file
@ -0,0 +1,3 @@
|
||||
# Mongoose with STM32, FreeRTOS kernel and FreeRTOS-TCP network stack
|
||||
|
||||
The `-DMG_ARCH=MG_ARCH_FREERTOS_TCP` compilation flag enables FreeRTOS+TCP support.
|
@ -33,7 +33,8 @@ static void fn(void *args) {
|
||||
// int delay_ms = *(int *) args;
|
||||
for (;;) {
|
||||
led_toggle();
|
||||
vTaskDelay(pdMS_TO_TICKS(300));
|
||||
spin(500000);
|
||||
// vTaskDelay(pdMS_TO_TICKS(0));
|
||||
};
|
||||
(void) args;
|
||||
}
|
||||
@ -41,7 +42,8 @@ static void fn(void *args) {
|
||||
int main(void) {
|
||||
init_ram();
|
||||
init_hardware();
|
||||
xTaskCreate(fn, "server", 512, NULL, configMAX_PRIORITIES - 1, NULL);
|
||||
vTaskStartScheduler();
|
||||
fn(NULL);
|
||||
// xTaskCreate(fn, "server", 512, NULL, configMAX_PRIORITIES - 1, NULL);
|
||||
// vTaskStartScheduler();
|
||||
return 0;
|
||||
}
|
||||
|
@ -22,36 +22,29 @@
|
||||
#define configENABLE_BACKWARD_COMPATIBILITY 0
|
||||
#define configNUM_THREAD_LOCAL_STORAGE_POINTERS 5
|
||||
|
||||
/* Memory allocation related definitions. */
|
||||
#define configSUPPORT_STATIC_ALLOCATION 0
|
||||
#define configSUPPORT_DYNAMIC_ALLOCATION 1
|
||||
#define configTOTAL_HEAP_SIZE ((size_t)(8 * 1024))
|
||||
#define configAPPLICATION_ALLOCATED_HEAP 0
|
||||
|
||||
/* Hook function related definitions. */
|
||||
#define configUSE_IDLE_HOOK 0
|
||||
#define configUSE_TICK_HOOK 0
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 0
|
||||
#define configUSE_MALLOC_FAILED_HOOK 0
|
||||
#define configUSE_DAEMON_TASK_STARTUP_HOOK 0
|
||||
|
||||
/* Run time and task stats gathering related definitions. */
|
||||
#define configGENERATE_RUN_TIME_STATS 0
|
||||
#define configUSE_TRACE_FACILITY 0
|
||||
#define configUSE_STATS_FORMATTING_FUNCTIONS 0
|
||||
|
||||
/* Co-routine related definitions. */
|
||||
#define configUSE_CO_ROUTINES 0
|
||||
#define configMAX_CO_ROUTINE_PRIORITIES 1
|
||||
|
||||
/* Software timer related definitions. */
|
||||
#define configUSE_TIMERS 0
|
||||
#define configTIMER_TASK_PRIORITY 3
|
||||
#define configTIMER_QUEUE_LENGTH 10
|
||||
#define configTIMER_TASK_STACK_DEPTH configMINIMAL_STACK_SIZE
|
||||
|
||||
/* Interrupt nesting behaviour configuration. */
|
||||
/* Cortex-M specific definitions. */
|
||||
#ifdef __NVIC_PRIO_BITS
|
||||
#define configPRIO_BITS __NVIC_PRIO_BITS
|
||||
#else
|
||||
@ -61,34 +54,29 @@
|
||||
#define configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY 5
|
||||
#define configKERNEL_INTERRUPT_PRIORITY \
|
||||
(configLIBRARY_LOWEST_INTERRUPT_PRIORITY << (8 - configPRIO_BITS))
|
||||
/* !!!! configMAX_SYSCALL_INTERRUPT_PRIORITY must not be set to zero !!!!
|
||||
See http://www.FreeRTOS.org/RTOS-Cortex-M3-M4.html. */
|
||||
#define configMAX_SYSCALL_INTERRUPT_PRIORITY \
|
||||
(configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS))
|
||||
|
||||
/* FreeRTOS MPU specific definitions. */
|
||||
#define configINCLUDE_APPLICATION_DEFINED_PRIVILEGED_FUNCTIONS 0
|
||||
|
||||
/* Optional functions - most linkers will remove unused functions anyway. */
|
||||
#define INCLUDE_vTaskPrioritySet 0
|
||||
#define INCLUDE_uxTaskPriorityGet 0
|
||||
#define INCLUDE_vTaskDelete 0
|
||||
#define INCLUDE_vTaskSuspend 0
|
||||
#define INCLUDE_xResumeFromISR 0
|
||||
#define INCLUDE_vTaskDelayUntil 0
|
||||
#define INCLUDE_vTaskPrioritySet 1
|
||||
#define INCLUDE_uxTaskPriorityGet 1
|
||||
#define INCLUDE_vTaskDelete 1
|
||||
#define INCLUDE_vTaskSuspend 1
|
||||
#define INCLUDE_xResumeFromISR 1
|
||||
#define INCLUDE_vTaskDelayUntil 1
|
||||
#define INCLUDE_vTaskDelay 1
|
||||
#define INCLUDE_xTaskGetSchedulerState 0
|
||||
#define INCLUDE_xTaskGetCurrentTaskHandle 0
|
||||
#define INCLUDE_uxTaskGetStackHighWaterMark 0
|
||||
#define INCLUDE_xTaskGetIdleTaskHandle 0
|
||||
#define INCLUDE_eTaskGetState 0
|
||||
#define INCLUDE_xEventGroupSetBitFromISR 0
|
||||
#define INCLUDE_xTimerPendFunctionCall 0
|
||||
#define INCLUDE_xTaskAbortDelay 0
|
||||
#define INCLUDE_xTaskGetHandle 0
|
||||
#define INCLUDE_xTaskResumeFromISR 0
|
||||
#define INCLUDE_xTaskGetSchedulerState 1
|
||||
#define INCLUDE_xTaskGetCurrentTaskHandle 1
|
||||
#define INCLUDE_uxTaskGetStackHighWaterMark 1
|
||||
#define INCLUDE_xTaskGetIdleTaskHandle 1
|
||||
#define INCLUDE_eTaskGetState 1
|
||||
#define INCLUDE_xEventGroupSetBitFromISR 1
|
||||
#define INCLUDE_xTimerPendFunctionCall 1
|
||||
#define INCLUDE_xTaskAbortDelay 1
|
||||
#define INCLUDE_xTaskGetHandle 1
|
||||
#define INCLUDE_xTaskResumeFromISR 1
|
||||
|
||||
/* Redirect FreeRTOS port interrupts. */
|
||||
#define vPortSVCHandler SVC_handler
|
||||
#define xPortPendSVHandler pending_SV_handler
|
||||
#define xPortSysTickHandler SysTick_handler
|
@ -1,4 +1,4 @@
|
||||
.cpu cortex-m0
|
||||
.cpu cortex-m3
|
||||
.thumb
|
||||
|
||||
.word _estack /* stack top address */
|
||||
|
@ -1,67 +1,18 @@
|
||||
// Copyright (c) 2018-2021 Cesanta Software Limited
|
||||
// All rights reserved
|
||||
//
|
||||
// TRM: https://www.st.com/resource/en/reference_manual/cd00171190.pdf
|
||||
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include "mcu.h"
|
||||
|
||||
#define LED_PIN 13 // PC13
|
||||
#define TX_PIN 9 // PA9
|
||||
#define RX_PIN 10 // PA10
|
||||
#define BIT(x) ((uint32_t) 1 << (x))
|
||||
|
||||
// RCC registers, TRM section 7.3
|
||||
struct rcc {
|
||||
volatile uint32_t CR, CFGR, CIR, APB2RSTR, APB1RSTR, AHBENR;
|
||||
volatile uint32_t APB2ENR, APB1ENR, BDCR, CSR;
|
||||
};
|
||||
#define RCC ((struct rcc *) 0x40021000)
|
||||
|
||||
// GPIO registers, TRM section 9.2
|
||||
struct gpio {
|
||||
volatile uint32_t CRL, CRH, IDR, ODR, BSRR, BRR, LCKR;
|
||||
};
|
||||
#define GPIOA ((struct gpio *) 0x40010800)
|
||||
#define GPIOB ((struct gpio *) 0x4001c000)
|
||||
#define GPIOC ((struct gpio *) 0x40011000)
|
||||
// enum { MODE_INPUT = 0, MODE_OUTPUT_1, MODE_OUTPUT_2, MODE_OUTPUT_3 };
|
||||
|
||||
// UART registers, TRM section 27.6
|
||||
struct uart {
|
||||
volatile uint32_t SR, DR, BRR, CR1, CR2, CR3, GTPR;
|
||||
};
|
||||
#define UART1 ((struct uart *) 0x40013800)
|
||||
#define UART2 ((struct uart *) 0x40004400)
|
||||
#define UART3 ((struct uart *) 0x40004800)
|
||||
#define UART4 ((struct uart *) 0x40004c00)
|
||||
#define UART5 ((struct uart *) 0x40005000)
|
||||
#define UART_HAS_DATA(u) ((u)->SR & BIT(5)) // RXNE
|
||||
#define UART_READ(u) ((u)->DR & 255)
|
||||
|
||||
static inline void setreg(uint32_t r, uint32_t clear_mask, uint32_t set_mask) {
|
||||
r &= ~(clear_mask);
|
||||
r |= (set_mask);
|
||||
}
|
||||
|
||||
static inline void pinmode(struct gpio *gpio, uint32_t pin, uint32_t mode) {
|
||||
uint32_t shift = ((pin) -8) * 4;
|
||||
setreg(gpio->CRH, 0xf << shift, mode << shift);
|
||||
}
|
||||
|
||||
static inline void init_ram(void) {
|
||||
extern uint32_t _bss_start, _bss_end;
|
||||
extern uint32_t _data_start, _data_end, _data_flash_start;
|
||||
memset(&_bss_start, 0, ((char *) &_bss_end - (char *) &_bss_start));
|
||||
memcpy(&_data_start, &_data_flash_start,
|
||||
((char *) &_data_end - (char *) &_data_start));
|
||||
}
|
||||
// These are NUCLEO-F103RB settings - adjust for your specific board
|
||||
#define RAM_SIZE 20480 // RAM size on this device, needed by link.ld
|
||||
#define ROM_SIZE 131072 // Flash size for this device, needed by link.ld
|
||||
#define LED1 PIN('A', 5) // On-board LED pin
|
||||
|
||||
static inline void led_toggle(void) {
|
||||
GPIOC->ODR ^= (1 << LED_PIN);
|
||||
gpio_toggle(LED1);
|
||||
}
|
||||
|
||||
static inline void init_hardware(void) {
|
||||
RCC->APB2ENR |= BIT(4); // GPIOC, for LED on PC13
|
||||
pinmode(GPIOC, LED_PIN, 0b0110); // open drain, output 2
|
||||
RCC->APB2ENR |= BIT(2) | BIT(3) | BIT(4); // Init GPIO banks A,B,C
|
||||
gpio_init(LED1, OUTPUT); // Set LED
|
||||
}
|
||||
|
@ -1,9 +1,9 @@
|
||||
ENTRY(_reset)
|
||||
_estack = 0x20001000;
|
||||
ENTRY(_reset);
|
||||
MEMORY {
|
||||
rom(rx) : ORIGIN = 0x08000000, LENGTH = 128k
|
||||
ram(rwx) : ORIGIN = 0x20000000, LENGTH = 20k
|
||||
ram(rwx) : ORIGIN = 0x20000000, LENGTH = RAM_SIZE
|
||||
rom(rx) : ORIGIN = 0x08000000, LENGTH = ROM_SIZE
|
||||
}
|
||||
_estack = 0x20000000 + RAM_SIZE;
|
||||
SECTIONS {
|
||||
.text : { *(.text*) } > rom
|
||||
.rodata : { *(.rodata*) } > rom
|
||||
|
40
examples/stm32/stm32f1/mcu.h
Normal file
40
examples/stm32/stm32f1/mcu.h
Normal file
@ -0,0 +1,40 @@
|
||||
// Copyright (c) 2018-2021 Cesanta Software Limited
|
||||
// All rights reserved
|
||||
// TRM: https://www.st.com/resource/en/reference_manual/cd00171190.pdf
|
||||
// clang-format off
|
||||
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
static inline void spin(uint32_t count) { while (count--) asm("nop"); }
|
||||
static inline void setreg(volatile uint32_t *r, uint32_t clear_mask, uint32_t set_mask) { *r &= ~clear_mask; *r |= set_mask; }
|
||||
|
||||
#define BIT(x) ((uint32_t) 1 << (x))
|
||||
#define PIN(bank, num) ((((bank) - 'A') << 8) | (num))
|
||||
|
||||
// RCC registers, TRM section 7.3, memory map section 3.3
|
||||
struct rcc { volatile uint32_t CR, CFGR, CIR, APB2RSTR, APB1RSTR, AHBENR, APB2ENR, APB1ENR, BDCR, CSR; };
|
||||
#define RCC ((struct rcc *) 0x40021000)
|
||||
|
||||
static inline void init_ram(void) {
|
||||
extern uint32_t _bss_start, _bss_end;
|
||||
extern uint32_t _data_start, _data_end, _data_flash_start;
|
||||
memset(&_bss_start, 0, ((char *) &_bss_end - (char *) &_bss_start));
|
||||
memcpy(&_data_start, &_data_flash_start, ((char *) &_data_end - (char *) &_data_start));
|
||||
}
|
||||
|
||||
// GPIO registers, TRM section 9.2, memory map section 3.3, regs 9.1.0
|
||||
enum { GPIO_OUT_PP, GPIO_OUT_OD, GPIO_AF_PP, GPIO_AF_OD, GPIO_ANA = 0, GPIO_FLOATING, GPIO_PULLED }; // 9.1.0
|
||||
enum { GPIO_IN, GPIO_OUT_10MHZ, GPIO_OUT_2MHZ, GPIO_OUT_50MHZ }; // 9.1.0
|
||||
enum { OUTPUT = (GPIO_OUT_PP << 2) | GPIO_OUT_2MHZ, INPUT = (GPIO_FLOATING << 2) | GPIO_IN, INPUT_PULLUP = (GPIO_PULLED << 2) | GPIO_IN};
|
||||
struct gpio { volatile uint32_t CRL, CRH, IDR, ODR, BSRR, BRR, LCKR; };
|
||||
static inline struct gpio *gpio_bank(uint16_t pin) { return (struct gpio *) (0x40010800 + 0x400 * (pin >> 8)); }
|
||||
static inline void gpio_on(uint16_t pin) { gpio_bank(pin)->ODR |= BIT(pin & 255); }
|
||||
static inline void gpio_off(uint16_t pin) { gpio_bank(pin)->ODR &= ~BIT(pin & 255); }
|
||||
static inline void gpio_toggle(uint16_t pin) { gpio_bank(pin)->ODR ^= BIT(pin & 255); }
|
||||
static inline void gpio_init(uint16_t pin, uint32_t mode) {
|
||||
uint8_t n = pin & 255, shift = (n < 8 ? n : (n - 8)) * 4;
|
||||
volatile uint32_t *reg = n < 8 ? &gpio_bank(pin)->CRL : &gpio_bank(pin)->CRH;
|
||||
setreg(reg, 15 << shift, mode << shift);
|
||||
}
|
||||
// clang-format on
|
Loading…
x
Reference in New Issue
Block a user