Published: Sep 15, 2022

STM32F030F4 - Bare Metal - Blink

Introduction

This post builds upon the code and techniques from “Bare Metal - Getting Started” to add a makefile and utilize C code. The goal is to toggle GPIO A4 which is connected to the onboard LED.

Linker Script

The linker script now contains definitions for SECTIONS which store specific parts of the application.

_estack = 0x20001000;
_Min_Leftover_RAM = 0x400;

MEMORY
{
    FLASH ( rx )      : ORIGIN = 0x08000000, LENGTH = 16K
    RAM ( rxw )       : ORIGIN = 0x20000000, LENGTH = 4K
}

SECTIONS
{
  /* The vector table goes at the start of flash. */
  .vector_table :
  {
    . = ALIGN(4);
    KEEP (*(.vector_table))
    . = ALIGN(4);
  } >FLASH
  /* The 'text' section contains the main program code. */
  .text :
  {
    . = ALIGN(4);
    *(.text)
    *(.text*)
    . = ALIGN(4);
  } >FLASH
  /* The 'rodata' section contains read-only data,
   * constants, strings, information that won't change. */
  .rodata :
  {
    . = ALIGN(4);
    *(.rodata)
    *(.rodata*)
    . = ALIGN(4);
  } >FLASH
  /* The 'data' section is space set aside in RAM for
   * things like variables, which can change. */
  _sidata = .;
  .data : AT(_sidata)
  {
    . = ALIGN(4);
    /* Mark start/end locations for the 'data' section. */
    _sdata = .;
    *(.data)
    *(.data*)
    _edata = .;
    . = ALIGN(4);
  } >RAM
  /* The 'bss' section is similar to the 'data' section,
   * but its space is initialized to all 0s at the
   * start of the program. */
  .bss :
  {
    . = ALIGN(4);
    /* Also mark the start/end of the BSS section. */
    _sbss = .;
    *(.bss)
    *(.bss*)
    *(COMMON)
    . = ALIGN(4);
    _ebss = .;
  } >RAM
  /* Space set aside for the application's heap/stack. */
  .dynamic_allocations :
  {
    . = ALIGN(4);
    _ssystem_ram = .;
    . = . + _Min_Leftover_RAM;
    . = ALIGN(4);
    _esystem_ram = .;
  } >RAM
}

Vector Table

The vector table is copied from the STM32CubeF0 repository and can be found in the startup_stm32f030x6.s file. The startup code at the beginning has been moved into a seperate boot.s file leaving only the vector table and default interrupt handler.

.syntax unified
.cpu cortex-m0
.fpu softvfp
.thumb
.global vtable
/*
 * The vector table.
 */
.type vtable, %object
.section .vector_table,"a",%progbits
vtable:
  .word  _estack
  .word  Reset_Handler
  .word  NMI_Handler
  .word  HardFault_Handler
  .word  0
  .word  0
  .word  0
  .word  0
  .word  0
  .word  0
  .word  0
  .word  SVC_Handler
  .word  0
  .word  0
  .word  PendSV_Handler
  .word  SysTick_Handler
  .word  WWDG_IRQHandler                   /* Window WatchDog              */
  .word  0                                 /* Reserved                     */
  .word  RTC_IRQHandler                    /* RTC through the EXTI line    */
  .word  FLASH_IRQHandler                  /* FLASH                        */
  .word  RCC_IRQHandler                    /* RCC                          */
  .word  EXTI0_1_IRQHandler                /* EXTI Line 0 and 1            */
  .word  EXTI2_3_IRQHandler                /* EXTI Line 2 and 3            */
  .word  EXTI4_15_IRQHandler               /* EXTI Line 4 to 15            */
  .word  0                                 /* Reserved                     */
  .word  DMA1_Channel1_IRQHandler          /* DMA1 Channel 1               */
  .word  DMA1_Channel2_3_IRQHandler        /* DMA1 Channel 2 and Channel 3 */
  .word  DMA1_Channel4_5_IRQHandler        /* DMA1 Channel 4 and Channel 5 */
  .word  ADC1_IRQHandler                   /* ADC1                         */
  .word  TIM1_BRK_UP_TRG_COM_IRQHandler    /* TIM1 Break, Update, Trigger and Commutation */
  .word  TIM1_CC_IRQHandler                /* TIM1 Capture Compare         */
  .word  0                                 /* Reserved                     */
  .word  TIM3_IRQHandler                   /* TIM3                         */
  .word  0                                 /* Reserved                     */
  .word  0                                 /* Reserved                     */
  .word  TIM14_IRQHandler                  /* TIM14                        */
  .word  0                                 /* Reserved                     */
  .word  TIM16_IRQHandler                  /* TIM16                        */
  .word  TIM17_IRQHandler                  /* TIM17                        */
  .word  I2C1_IRQHandler                   /* I2C1                         */
  .word  0                                 /* Reserved                     */
  .word  SPI1_IRQHandler                   /* SPI1                         */
  .word  0                                 /* Reserved                     */
  .word  USART1_IRQHandler                 /* USART1                       */
  .word  0                                 /* Reserved                     */
  .word  0                                 /* Reserved                     */
  .word  0                                 /* Reserved                     */
  .word  0                                 /* Reserved                     */
  // 48

  // (Location to boot from for RAM startup)
  #define boot_ram_base  0xF108F85F
  .word boot_ram_base
  /*
   * Setup weak aliases for each exception handler to the
   * default one. These can be updated later, or just
   * overridden since they're weak refs.
   * The reset_handler is set up separately.
   */
  .weak      NMI_Handler
  .thumb_set NMI_Handler,Default_Handler

  .weak      HardFault_Handler
  .thumb_set HardFault_Handler,Default_Handler

  .weak      SVC_Handler
  .thumb_set SVC_Handler,Default_Handler

  .weak      PendSV_Handler
  .thumb_set PendSV_Handler,Default_Handler

  .weak      SysTick_Handler
  .thumb_set SysTick_Handler,Default_Handler

  .weak      WWDG_IRQHandler
  .thumb_set WWDG_IRQHandler,Default_Handler

  .weak      RTC_IRQHandler
  .thumb_set RTC_IRQHandler,Default_Handler

  .weak      FLASH_IRQHandler
  .thumb_set FLASH_IRQHandler,Default_Handler

  .weak      RCC_IRQHandler
  .thumb_set RCC_IRQHandler,Default_Handler

  .weak      EXTI0_1_IRQHandler
  .thumb_set EXTI0_1_IRQHandler,Default_Handler

  .weak      EXTI2_3_IRQHandler
  .thumb_set EXTI2_3_IRQHandler,Default_Handler

  .weak      EXTI4_15_IRQHandler
  .thumb_set EXTI4_15_IRQHandler,Default_Handler

  .weak      DMA1_Channel1_IRQHandler
  .thumb_set DMA1_Channel1_IRQHandler,Default_Handler

  .weak      DMA1_Channel2_3_IRQHandler
  .thumb_set DMA1_Channel2_3_IRQHandler,Default_Handler

  .weak      DMA1_Channel4_5_IRQHandler
  .thumb_set DMA1_Channel4_5_IRQHandler,Default_Handler

  .weak      ADC1_IRQHandler
  .thumb_set ADC1_IRQHandler,Default_Handler

  .weak      TIM1_BRK_UP_TRG_COM_IRQHandler
  .thumb_set TIM1_BRK_UP_TRG_COM_IRQHandler,Default_Handler

  .weak      TIM1_CC_IRQHandler
  .thumb_set TIM1_CC_IRQHandler,Default_Handler

  .weak      TIM3_IRQHandler
  .thumb_set TIM3_IRQHandler,Default_Handler

  .weak      TIM14_IRQHandler
  .thumb_set TIM14_IRQHandler,Default_Handler

  .weak      TIM16_IRQHandler
  .thumb_set TIM16_IRQHandler,Default_Handler

  .weak      TIM17_IRQHandler
  .thumb_set TIM17_IRQHandler,Default_Handler

  .weak      I2C1_IRQHandler
  .thumb_set I2C1_IRQHandler,Default_Handler

  .weak      SPI1_IRQHandler
  .thumb_set SPI1_IRQHandler,Default_Handler

  .weak      USART1_IRQHandler
  .thumb_set USART1_IRQHandler,Default_Handler

.size vtable, .-vtable
/*
 * A 'Default' interrupt handler. This is where interrupts
 * which are not otherwise configured will go.
 * Here it's just an infinite loop.
 */
.section .text.Default_Handler,"ax",%progbits
Default_Handler:
  default_interrupt_loop:
    B default_interrupt_loop
.size Default_Handler, .-Default_Handler

Boot

Following code will take care of copying initial data from flash to RAM, filling empty space with 0’s and finally branching to the main() method.

.syntax unified
.cpu cortex-m0
.fpu softvfp
.thumb

.global Reset_Handler

.type Reset_Handler, %function
Reset_Handler:
  LDR  r0, =_estack
  MOV  sp, r0   /* set stack pointer */

// Copy data from flash to RAM data init section
MOVS r0, #0

// Load the start/end addresses of the data section,
// and the start of the data init section.
LDR  r1, =_sdata
LDR  r2, =_edata
LDR  r3, =_sidata
B    copy_sidata_loop

copy_sidata:
  // Offset the data init section by our copy progress.
  LDR  r4, [r3, r0]
  // Copy the current word into data, and increment.
  STR  r4, [r1, r0]
  ADDS r0, r0, #4
copy_sidata_loop:
  // Unless we've copied the whole data section, copy the
  // next word from sidata->data.
  ADDS r4, r0, r1
  CMP  r4, r2
  BCC  copy_sidata

// Once we are done copying the data section into RAM,
// move on to filling the BSS section with 0s.
MOVS r0, #0
LDR  r1, =_sbss
LDR  r2, =_ebss
B    reset_bss_loop

// Fill the BSS segment with '0's.
reset_bss:
  // Store a 0 and increment by a word.
  STR  r0, [r1]
  ADDS r1, r1, #4
reset_bss_loop:
  // We'll use R1 to count progress here; if we aren't
  // done, reset the next word and increment.
  CMP  r1, r2
  BCC  reset_bss
  // Branch to the 'main' method.
  B    main
.size Reset_Handler, .-Reset_Handler

A little help

We’ll take a few files from the STM32CubeF0 repository to avoid having to look up peripheral register addresses and NVIC (vector table) configurations. Those files are:

STM32CubeF0/Drivers/CMSIS/Device/ST/STM32F0xx/Include/stm32f030x6.h
STM32CubeF0/Drivers/CMSIS/Include/core_cm0.h
STM32CubeF0/Drivers/CMSIS/Include/cmsis_version.h
STM32CubeF0/Drivers/CMSIS/Include/cmsis_gcc.h
STM32CubeF0/Drivers/CMSIS/Include/cmsis_compiler.h
STM32CubeF0/Drivers/CMSIS/Device/ST/STM32F0xx/Include/system_stm32f0xx.h

Let’s copy them in a subdirectory in our project root resulting in the following structure:

📦bare-metal-blink
 ┣ 📂STM32CubeF0
 ┃ ┣ 📜cmsis_compiler.h
 ┃ ┣ 📜cmsis_gcc.h
 ┃ ┣ 📜cmsis_version.h
 ┃ ┣ 📜core_cm0.h
 ┃ ┣ 📜stm32f030x6.h
 ┃ ┗ 📜system_stm32f0xx.h
 ┣ 📜STM32F030F4.ld
 ┣ 📜boot.s
 ┗ 📜startup_stm32f030x6.s

Main.c

It’s finally time for some C code. Following code toggles the onboard LED at GPIOA4 every second.

#include "STM32CubeF0/stm32f030x6.h"

#define LED_PIN 4

int SysTickMsCounter = 0;

void SysTick_Handler() {
    SysTickMsCounter++;
}

void sleep(int ms) {
    // enable SysTick timer
    SysTick->CTRL |= SysTick_CTRL_ENABLE_Msk;
    // wait
    SysTickMsCounter = 0;
    while(SysTickMsCounter < ms);
    // disable SysTick timer
    SysTick->CTRL &= ~SysTick_CTRL_ENABLE_Msk;
}

int main(void)
{
    // Default internal clock @ 8MHz
    const int SystemClock = 8000000;

    // Setup SysTick timer to generate an interrupt every millisecond
    SysTick->LOAD = (uint32_t)((SystemClock / 1000) -1);
    SysTick->VAL = 0;
    SysTick->CTRL = (SysTick_CTRL_CLKSOURCE_Msk | SysTick_CTRL_TICKINT_Msk);

    // Setup GPIO as push/pull low speed
    RCC->AHBENR |= RCC_AHBENR_GPIOAEN;
    GPIOA->MODER &= ~(0x3 << (LED_PIN*2));
    GPIOA->MODER |= (0x1 << (LED_PIN*2));
    GPIOA->OTYPER &= ~(1 << LED_PIN);

    while (1)
    {
        // toggle gpio
        GPIOA->ODR ^= (1 << LED_PIN);

        sleep(1000);
    }
    return 0;
}

Makefile

Now while we could compile it manually a makefile makes this a lot easier.

TARGET = main

# Define the linker script location and chip architecture.
LD_SCRIPT = STM32F030F4.ld
MCU_SPEC  = cortex-m0

# Toolchain definitions (ARM bare metal defaults)
TOOLCHAIN = /usr
CC = $(TOOLCHAIN)/bin/arm-none-eabi-gcc
AS = $(TOOLCHAIN)/bin/arm-none-eabi-as
LD = $(TOOLCHAIN)/bin/arm-none-eabi-ld
OC = $(TOOLCHAIN)/bin/arm-none-eabi-objcopy
OD = $(TOOLCHAIN)/bin/arm-none-eabi-objdump
OS = $(TOOLCHAIN)/bin/arm-none-eabi-size

# Assembly directives.
ASFLAGS += -c
ASFLAGS += -O0
ASFLAGS += -mcpu=$(MCU_SPEC)
ASFLAGS += -mthumb
ASFLAGS += -Wall
# (Set error messages to appear on a single line.)
ASFLAGS += -fmessage-length=0

# C compilation directives
CFLAGS += -mcpu=$(MCU_SPEC)
CFLAGS += -mthumb
CFLAGS += -Wall
CFLAGS += -g
# (Set error messages to appear on a single line.)
CFLAGS += -fmessage-length=0
# (Set system to ignore semihosted junk)
CFLAGS += --specs=nosys.specs

# Linker directives.
LSCRIPT = ./$(LD_SCRIPT)
LFLAGS += -mcpu=$(MCU_SPEC)
LFLAGS += -mthumb
LFLAGS += -Wall
LFLAGS += -Wall
LFLAGS += --specs=nosys.specs
LFLAGS += -nostdlib
LFLAGS += -lgcc
LFLAGS += -T$(LSCRIPT)

STARTUP = ./startup_stm32f030x6.s
BOOT_S   = ./boot.s
MAIN_C    = ./main.c

OBJS =  $(STARTUP:.s=.o)
OBJS += $(BOOT_S:.s=.o)
OBJS += $(MAIN_C:.c=.o)

.PHONY: all
all: $(TARGET).bin

%.o: %.s
	mkdir build -p
	$(CC) -x assembler-with-cpp $(ASFLAGS) $< -o build/$@

%.o: %.c
	$(CC) -c $(CFLAGS) $(INCLUDE) $< -o build/$@

$(TARGET).elf: $(OBJS)
	$(CC) $(addprefix build/, $^) $(LFLAGS) -o build/$@

$(TARGET).bin: $(TARGET).elf
	$(OC) -S -O binary build/$< build/$@
	$(OS) build/$<

.PHONY: clean
clean:
	rm -vf build/*

Build

Make sure you have all the files in place:

📦bare-metal-blink
 ┣ 📂STM32CubeF0
 ┃ ┣ 📜cmsis_compiler.h
 ┃ ┣ 📜cmsis_gcc.h
 ┃ ┣ 📜cmsis_version.h
 ┃ ┣ 📜core_cm0.h
 ┃ ┣ 📜stm32f030x6.h
 ┃ ┗ 📜system_stm32f0xx.h
 ┣ 📜Makefile
 ┣ 📜STM32F030F4.ld
 ┣ 📜boot.s
 ┣ 📜main.c
 ┗ 📜startup_stm32f030x6.s

Then start the build

make all

Now you should see a build/ directory with a few files. main.elf contains debugging symbols and should only be used with gdb. main.bin contains the application binary without debugging symbols.

Flash

To flash main.bin run:

st-flash write build/main.bin 0x08000000

Checking GPIO A4 with a logic analyzer shows that the code is working as expected and toggling the pin every second.