Project 3: Bare-Metal LED Blinker

Back to ARM Deep Dive


Quick Reference

Attribute Details
Difficulty Advanced
Time Estimate 1-2 weeks
Language C with ARM Assembly startup
Prerequisites ARM assembly basics (Project 2), C programming, hex/bitwise operations
Key Topics Vector table, linker scripts, GPIO, memory-mapped I/O, bare-metal boot
Hardware Required STM32 Nucleo board (~$15) OR Raspberry Pi
Book Reference “Making Embedded Systems, 2nd Edition” by Elecia White

Learning Objectives

By completing this project, you will:

  1. Understand ARM boot sequence - Know exactly what happens from power-on to your code
  2. Write a vector table - Create the exception vectors that ARM requires
  3. Create linker scripts - Define memory layout for Flash and RAM
  4. Configure GPIO registers - Control hardware pins through memory-mapped I/O
  5. Create delays without an OS - Implement timing using cycle counting or timers
  6. Experience true bare-metal programming - No OS, no libraries, just you and silicon

Theoretical Foundation

Core Concepts

1. The ARM Boot Sequence

When an ARM Cortex-M processor powers on, it follows a precise sequence:

Power On
    |
    v
+-------------------+
| 1. Load SP from   |  CPU reads 4 bytes from address 0x00000000
|    address 0x0000 |  This becomes the initial Stack Pointer
+-------------------+
    |
    v
+-------------------+
| 2. Load PC from   |  CPU reads 4 bytes from address 0x00000004
|    address 0x0004 |  This is the Reset Handler address
+-------------------+
    |
    v
+-------------------+
| 3. Jump to Reset  |  CPU begins executing at Reset Handler
|    Handler        |
+-------------------+
    |
    v
+-------------------+
| 4. Reset Handler: |
|    - Copy .data   |  Copy initialized data from Flash to RAM
|    - Zero .bss    |  Clear uninitialized data section
|    - Call main()  |
+-------------------+
    |
    v
+-------------------+
| 5. main() runs    |  Your code executes
|    (never returns)|  In bare-metal, main loops forever
+-------------------+

Key Insight: The CPU has NO idea what code to run. It simply reads two 32-bit values from the start of memory. YOUR code must be there.

2. The Vector Table

The vector table is a list of addresses at the start of Flash memory:

Vector Table Layout (Cortex-M):
+----------+------------------+---------------------------+
| Address  | Vector           | Purpose                   |
+----------+------------------+---------------------------+
| 0x0000   | Initial SP       | Stack pointer value       |
| 0x0004   | Reset            | Reset handler address     |
| 0x0008   | NMI              | Non-maskable interrupt    |
| 0x000C   | HardFault        | All fault handler         |
| 0x0010   | MemManage        | Memory management fault   |
| 0x0014   | BusFault         | Bus fault                 |
| 0x0018   | UsageFault       | Usage fault               |
| 0x001C   | Reserved         | -                         |
| 0x0020   | Reserved         | -                         |
| 0x0024   | Reserved         | -                         |
| 0x0028   | Reserved         | -                         |
| 0x002C   | SVCall           | Supervisor call (SVC)     |
| 0x0030   | Debug Monitor    | Debug monitor             |
| 0x0034   | Reserved         | -                         |
| 0x0038   | PendSV           | Pendable service request  |
| 0x003C   | SysTick          | System tick timer         |
| 0x0040+  | IRQ0, IRQ1...    | Peripheral interrupts     |
+----------+------------------+---------------------------+

In assembly:

    .section .vectors, "a"
    .word   _stack_top          @ 0x0000: Initial SP
    .word   reset_handler       @ 0x0004: Reset
    .word   nmi_handler         @ 0x0008: NMI
    .word   hardfault_handler   @ 0x000C: HardFault
    @ ... more vectors ...

3. Memory Map (STM32F4 Example)

Understanding where things live in memory is crucial:

STM32F4 Memory Map:
+------------------+------------------+
| Address Range    | Contents         |
+------------------+------------------+
| 0x0000_0000      | Aliased to Flash |
| ...              | or System memory |
+------------------+------------------+
| 0x0800_0000      | Flash Memory     | <-- Your code lives here
| ...              | (up to 2MB)      |
| 0x081F_FFFF      |                  |
+------------------+------------------+
| 0x1FFF_0000      | System Memory    | <-- Bootloader ROM
| ...              | (factory boot)   |
+------------------+------------------+
| 0x2000_0000      | SRAM             | <-- Your variables/stack
| ...              | (up to 256KB)    |
| 0x2003_FFFF      |                  |
+------------------+------------------+
| 0x4000_0000      | Peripherals      | <-- GPIO, UART, etc.
| ...              | APB1, APB2, AHB  |
| 0x5FFF_FFFF      |                  |
+------------------+------------------+
| 0xE000_0000      | System           | <-- NVIC, SysTick, etc.
| ...              | (Cortex-M core)  |
+------------------+------------------+

4. Linker Script Basics

The linker script tells the linker where to place code and data:

/* Memory regions */
MEMORY
{
    FLASH (rx)  : ORIGIN = 0x08000000, LENGTH = 512K
    RAM   (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
}

/* Section placement */
SECTIONS
{
    /* Vector table must be first in Flash */
    .vectors : {
        *(.vectors)
    } > FLASH

    /* Code goes in Flash */
    .text : {
        *(.text*)
        *(.rodata*)        /* Read-only data */
    } > FLASH

    /* Initialized data: stored in Flash, copied to RAM */
    .data : {
        _data_start = .;
        *(.data*)
        _data_end = .;
    } > RAM AT > FLASH

    /* Uninitialized data: just reserve space in RAM */
    .bss : {
        _bss_start = .;
        *(.bss*)
        *(COMMON)
        _bss_end = .;
    } > RAM

    /* Stack at end of RAM */
    _stack_top = ORIGIN(RAM) + LENGTH(RAM);
}

5. Memory-Mapped I/O

On ARM, peripherals are accessed like memory addresses:

GPIO Concept:
+-------------+                    +-------------+
| CPU         |  Address Bus       | GPIO        |
|             |====================>| Controller  |
|             |  Data Bus          |             |
|             |<===================>|    [pins]   |--->  LED
|             |                    |             |
+-------------+                    +-------------+

When you write to address 0x40020014, you're not writing
to RAM - you're writing to the GPIO Output Data Register!

GPIO Register Structure (STM32):

GPIOA Base: 0x40020000

+--------+-------------+----------------------------------------+
| Offset | Register    | Purpose                                |
+--------+-------------+----------------------------------------+
| 0x00   | MODER       | Mode (input/output/alternate/analog)   |
| 0x04   | OTYPER      | Output type (push-pull/open-drain)     |
| 0x08   | OSPEEDR     | Output speed                           |
| 0x0C   | PUPDR       | Pull-up/pull-down                      |
| 0x10   | IDR         | Input data (read pin states)           |
| 0x14   | ODR         | Output data (set pin states)           |
| 0x18   | BSRR        | Bit set/reset (atomic operations)      |
| 0x1C   | LCKR        | Lock configuration                     |
| 0x20   | AFRL        | Alternate function low (pins 0-7)      |
| 0x24   | AFRH        | Alternate function high (pins 8-15)    |
+--------+-------------+----------------------------------------+

6. The volatile Keyword

Critical for memory-mapped I/O:

// WITHOUT volatile - BROKEN:
uint32_t *gpio = (uint32_t *)0x40020014;
*gpio = 1;  // Compiler might optimize this away!
*gpio = 0;  // Or combine with next write!

// WITH volatile - CORRECT:
volatile uint32_t *gpio = (volatile uint32_t *)0x40020014;
*gpio = 1;  // Compiler MUST write to hardware
*gpio = 0;  // Compiler MUST write again, separately

// Why? The compiler assumes memory doesn't change unless
// your code changes it. Hardware registers DO change!

Why This Matters

Bare-metal programming is the foundation for:

  • Embedded systems: IoT devices, automotive, medical devices
  • Bootloaders: What runs before the OS
  • Real-time systems: When timing is critical
  • Security: Secure boot, hardware security modules
  • Understanding computers: This is how they REALLY work

Historical Context

Before operating systems, ALL programming was bare-metal. The first computer programs in the 1940s-50s directly manipulated hardware. Today, bare-metal is making a comeback:

  • IoT devices: Too small for OS overhead
  • Safety-critical: Medical devices, automotive (simpler = safer)
  • Performance: Game consoles, HPC, network switches
  • Security: Trusted execution environments

Project Specification

What You’ll Build

An LED blinker that runs directly on ARM hardware with NO operating system:

  1. Vector table and startup code
  2. Linker script for memory layout
  3. Clock configuration (optional but recommended)
  4. GPIO pin configuration
  5. Software delay loop
  6. Main loop that blinks LED

Requirements

Core Requirements:

  • Create valid vector table in Flash
  • Write reset handler that initializes .data and .bss
  • Configure GPIO pin as output
  • Toggle LED state
  • Implement delay (any method)
  • LED visibly blinks (~1Hz)

Extended Requirements:

  • Configure system clock (faster = more accurate timing)
  • Use SysTick timer for delay
  • Add UART output (see Project 4)
  • Blink pattern (SOS, heartbeat, etc.)
  • Button input to change blink rate

Hardware Options

Option 1: STM32 Nucleo-F411RE (~$15)

  • User LED on PA5
  • Button on PC13
  • Built-in ST-Link programmer
  • Most common choice for learning

Option 2: Raspberry Pi (any model)

  • GPIO pin 18 (physical pin 12)
  • Requires external LED + resistor
  • Boot from SD card
  • No debugger without extra hardware

Option 3: QEMU Emulation

  • qemu-system-arm -machine stm32f4-discovery
  • Limited peripheral emulation
  • Good for testing code without hardware

Example Output

Physical result: An LED on your board blinks at 1Hz

If you add serial output (Project 4):
$ screen /dev/ttyACM0 115200

Starting bare-metal LED blinker...
System clock: 16 MHz (default HSI)
GPIO configured: PA5 as output
Blink cycle: 500ms on, 500ms off

[LED ON]  - tick
[LED OFF] - tick
[LED ON]  - tick
...

Solution Architecture

High-Level Design

+-----------------------------------------------------------+
|                        Flash Memory                        |
+-----------------------------------------------------------+
| 0x08000000: Vector Table                                   |
|   +-- Initial SP: 0x20020000 (top of RAM)                 |
|   +-- Reset Handler: 0x08000100 (our startup code)        |
|   +-- Other handlers...                                    |
+-----------------------------------------------------------+
| 0x08000100: Startup Code (assembly)                        |
|   +-- Copy .data from Flash to RAM                        |
|   +-- Zero .bss section                                    |
|   +-- Call main()                                          |
+-----------------------------------------------------------+
| 0x08000200: main() and application code                    |
|   +-- init_gpio()                                          |
|   +-- loop: toggle LED, delay                              |
+-----------------------------------------------------------+
| 0x08001000: Read-only data (.rodata)                       |
+-----------------------------------------------------------+

+-----------------------------------------------------------+
|                         RAM                                |
+-----------------------------------------------------------+
| 0x20000000: .data (initialized variables)                  |
| 0x20000100: .bss (zero-initialized variables)              |
| ...                                                        |
| 0x2001FFF0: Stack (grows down)                             |
| 0x20020000: _stack_top                                     |
+-----------------------------------------------------------+

File Structure

bare-metal-blink/
+-- startup.s          # Vector table + reset handler (assembly)
+-- main.c             # Main application logic
+-- stm32f4.h          # Register definitions
+-- linker.ld          # Memory layout
+-- Makefile           # Build script
+-- README.md          # Documentation

Component Interaction

                      Power On
                          |
                          v
+------------------+     Vector Table     +------------------+
|                  |<----- reads ---------|                  |
|      Flash       |                      |    ARM CPU       |
| (startup.s)      |-------- PC --------->|                  |
|                  |     jumps to         |                  |
+------------------+     reset_handler    +------------------+
         |                                        |
         |                                        |
         v                                        v
+------------------+                      +------------------+
| reset_handler:   |                      | main():          |
| - init .data     |------- calls ------->| - init_gpio()    |
| - zero .bss      |                      | - while(1):      |
| - call main()    |                      |   - toggle LED   |
+------------------+                      |   - delay()      |
                                          +------------------+
                                                  |
                                                  | writes to
                                                  v
                                          +------------------+
                                          | GPIO Registers   |
                                          | (0x40020000)     |
                                          +------------------+
                                                  |
                                                  | controls
                                                  v
                                               [LED]

Implementation Guide

Environment Setup

Required Tools:

# Linux/macOS
sudo apt install gcc-arm-none-eabi     # ARM compiler
sudo apt install openocd               # Debugger/programmer
sudo apt install stlink-tools          # ST-Link utilities

# Verify installation
arm-none-eabi-gcc --version
openocd --version

# Create project directory
mkdir bare-metal-blink && cd bare-metal-blink

Hardware Setup (STM32 Nucleo):

  1. Connect Nucleo board via USB
  2. Board powers on, default firmware blinks LED
  3. Verify connection: st-info --probe

Project Files

Makefile:

# Toolchain
CC = arm-none-eabi-gcc
AS = arm-none-eabi-as
LD = arm-none-eabi-ld
OBJCOPY = arm-none-eabi-objcopy
SIZE = arm-none-eabi-size

# Flags
CFLAGS = -mcpu=cortex-m4 -mthumb -O0 -g -Wall
ASFLAGS = -mcpu=cortex-m4 -mthumb
LDFLAGS = -T linker.ld -nostdlib

# Files
TARGET = blink
OBJS = startup.o main.o

all: $(TARGET).bin

$(TARGET).elf: $(OBJS)
	$(CC) $(LDFLAGS) -o $@ $^

$(TARGET).bin: $(TARGET).elf
	$(OBJCOPY) -O binary $< $@
	$(SIZE) $<

startup.o: startup.s
	$(AS) $(ASFLAGS) -o $@ $<

main.o: main.c
	$(CC) $(CFLAGS) -c -o $@ $<

flash: $(TARGET).bin
	st-flash write $< 0x08000000

clean:
	rm -f *.o *.elf *.bin

.PHONY: all flash clean

Implementation Hints in Layers

Hint 1: Start with the Vector Table (startup.s)

The very first code to write - without this, nothing works:

    .syntax unified
    .cpu cortex-m4
    .thumb

    .section .vectors, "a"
    .word   _stack_top          @ 0x00: Initial Stack Pointer
    .word   reset_handler       @ 0x04: Reset Handler
    .word   nmi_handler         @ 0x08: NMI Handler
    .word   hardfault_handler   @ 0x0C: Hard Fault Handler
    .word   0                   @ 0x10: Reserved
    .word   0                   @ 0x14: Reserved
    .word   0                   @ 0x18: Reserved
    .word   0                   @ 0x1C: Reserved
    .word   0                   @ 0x20: Reserved
    .word   0                   @ 0x24: Reserved
    .word   0                   @ 0x28: Reserved
    .word   0                   @ 0x2C: Reserved
    .word   0                   @ 0x30: Reserved
    .word   0                   @ 0x34: Reserved
    .word   0                   @ 0x38: Reserved
    .word   0                   @ 0x3C: Reserved

    @ Default handlers (infinite loops)
    .thumb_func
nmi_handler:
hardfault_handler:
    b       .

    .section .text
    .thumb_func
    .global reset_handler
reset_handler:
    @ Copy .data from Flash to RAM
    ldr     r0, =_data_flash    @ Source (in Flash)
    ldr     r1, =_data_start    @ Destination (in RAM)
    ldr     r2, =_data_end      @ End address
copy_data:
    cmp     r1, r2
    bge     zero_bss
    ldr     r3, [r0], #4
    str     r3, [r1], #4
    b       copy_data

    @ Zero .bss section
zero_bss:
    ldr     r0, =_bss_start
    ldr     r1, =_bss_end
    mov     r2, #0
clear_bss:
    cmp     r0, r1
    bge     call_main
    str     r2, [r0], #4
    b       clear_bss

    @ Call main()
call_main:
    bl      main

    @ If main returns (it shouldn't), loop forever
    b       .

Hint 2: Create the Linker Script (linker.ld)

This defines memory layout - must match your specific chip:

/* STM32F411RE: 512KB Flash, 128KB RAM */
MEMORY
{
    FLASH (rx)  : ORIGIN = 0x08000000, LENGTH = 512K
    RAM   (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
}

/* Stack at top of RAM */
_stack_top = ORIGIN(RAM) + LENGTH(RAM);

SECTIONS
{
    /* Vector table at start of Flash */
    .vectors : {
        . = ALIGN(4);
        KEEP(*(.vectors))
        . = ALIGN(4);
    } > FLASH

    /* Code section */
    .text : {
        . = ALIGN(4);
        *(.text*)
        *(.rodata*)
        . = ALIGN(4);
    } > FLASH

    /* Store initial values for .data in Flash */
    _data_flash = .;

    /* Initialized data (copied to RAM at startup) */
    .data : AT(_data_flash) {
        . = ALIGN(4);
        _data_start = .;
        *(.data*)
        . = ALIGN(4);
        _data_end = .;
    } > RAM

    /* Uninitialized data (zeroed at startup) */
    .bss : {
        . = ALIGN(4);
        _bss_start = .;
        *(.bss*)
        *(COMMON)
        . = ALIGN(4);
        _bss_end = .;
    } > RAM
}

Hint 3: Register Definitions (stm32f4.h)

Create header with memory-mapped register definitions:

#ifndef STM32F4_H
#define STM32F4_H

#include <stdint.h>

/* Base addresses */
#define PERIPH_BASE     0x40000000U
#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000U)
#define GPIOA_BASE      (AHB1PERIPH_BASE + 0x0000U)
#define RCC_BASE        (AHB1PERIPH_BASE + 0x3800U)

/* RCC (Reset and Clock Control) */
typedef struct {
    volatile uint32_t CR;           /* 0x00 */
    volatile uint32_t PLLCFGR;      /* 0x04 */
    volatile uint32_t CFGR;         /* 0x08 */
    volatile uint32_t CIR;          /* 0x0C */
    volatile uint32_t AHB1RSTR;     /* 0x10 */
    volatile uint32_t AHB2RSTR;     /* 0x14 */
    volatile uint32_t AHB3RSTR;     /* 0x18 */
    uint32_t RESERVED0;             /* 0x1C */
    volatile uint32_t APB1RSTR;     /* 0x20 */
    volatile uint32_t APB2RSTR;     /* 0x24 */
    uint32_t RESERVED1[2];          /* 0x28-0x2C */
    volatile uint32_t AHB1ENR;      /* 0x30 - GPIO clock enable! */
    /* ... more registers ... */
} RCC_TypeDef;

#define RCC ((RCC_TypeDef *)RCC_BASE)
#define RCC_AHB1ENR_GPIOAEN (1 << 0)

/* GPIO (General Purpose I/O) */
typedef struct {
    volatile uint32_t MODER;    /* 0x00 Mode register */
    volatile uint32_t OTYPER;   /* 0x04 Output type */
    volatile uint32_t OSPEEDR;  /* 0x08 Output speed */
    volatile uint32_t PUPDR;    /* 0x0C Pull-up/pull-down */
    volatile uint32_t IDR;      /* 0x10 Input data */
    volatile uint32_t ODR;      /* 0x14 Output data */
    volatile uint32_t BSRR;     /* 0x18 Bit set/reset */
    volatile uint32_t LCKR;     /* 0x1C Lock */
    volatile uint32_t AFR[2];   /* 0x20-0x24 Alternate function */
} GPIO_TypeDef;

#define GPIOA ((GPIO_TypeDef *)GPIOA_BASE)

/* GPIO MODER values */
#define GPIO_MODER_INPUT  0x0
#define GPIO_MODER_OUTPUT 0x1
#define GPIO_MODER_AF     0x2
#define GPIO_MODER_ANALOG 0x3

#endif /* STM32F4_H */

Hint 4: Main Application (main.c)

The actual LED blinking logic:

#include "stm32f4.h"

/* LED is on PA5 (Nucleo board) */
#define LED_PIN 5

void delay(volatile uint32_t count) {
    while (count--) {
        __asm__("nop");  /* Prevent optimization */
    }
}

int main(void) {
    /* 1. Enable GPIOA clock */
    RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN;

    /* Small delay for clock to stabilize */
    delay(10);

    /* 2. Configure PA5 as output */
    /* Clear bits 11:10, then set to 01 (output mode) */
    GPIOA->MODER &= ~(0x3 << (LED_PIN * 2));
    GPIOA->MODER |= (GPIO_MODER_OUTPUT << (LED_PIN * 2));

    /* 3. Main loop - blink forever */
    while (1) {
        /* Toggle LED using XOR */
        GPIOA->ODR ^= (1 << LED_PIN);

        /* Delay approximately 500ms at 16MHz */
        /* This is very rough - tune for your clock */
        delay(800000);
    }

    return 0;  /* Never reached */
}

Hint 5: Debugging and Verification

Verify your binary is structured correctly:

# Build
make

# Examine sections
arm-none-eabi-objdump -h blink.elf

# Should show:
# .vectors at 0x08000000
# .text after .vectors
# .data in RAM, loaded from Flash

# Examine vector table
arm-none-eabi-objdump -s -j .vectors blink.elf

# Should show:
# First word = stack pointer
# Second word = reset handler address (odd = Thumb mode)

# Disassemble to verify code
arm-none-eabi-objdump -d blink.elf | head -100

# Flash to device
make flash

# Or use OpenOCD
openocd -f interface/stlink.cfg -f target/stm32f4x.cfg \
        -c "program blink.elf verify reset exit"

Interview Questions You Should Be Able to Answer

After completing this project, you should confidently answer:

  1. “What happens when an ARM Cortex-M processor powers on?”
    • Reads SP from 0x0000, PC from 0x0004
    • Jumps to reset handler
    • Handler initializes memory, calls main()
  2. “Why must GPIO registers be declared volatile?”
    • Hardware can change register values
    • Compiler assumes memory only changes via code
    • volatile prevents optimization of hardware accesses
  3. “What’s a linker script and why do you need one?”
    • Defines memory regions (Flash, RAM)
    • Places sections (.text, .data, .bss) in correct locations
    • Provides symbols for startup code (_stack_top, etc.)
  4. “How do you configure a GPIO pin as output on ARM?”
    • Enable peripheral clock in RCC
    • Set MODER register bits for output mode
    • Write to ODR or BSRR to control pin state
  5. “What’s the difference between .data and .bss sections?”
    • .data: initialized variables, stored in Flash, copied to RAM
    • .bss: uninitialized (zero-init) variables, just RAM space
  6. “How do you create a delay without an OS?”
    • Busy loop (count iterations)
    • SysTick timer
    • Peripheral timer
    • Cycle counting with DWT

Books That Will Help

Topic Book Chapter
ARM Startup Sequence “Making Embedded Systems” - White Chapter 3
Linker Scripts “Bare Metal C” - Oualline Chapter 2
Memory-Mapped I/O “CS:APP” - Bryant Chapter 9
GPIO Configuration STM32F4 Reference Manual GPIO Chapter
Clock Configuration “Making Embedded Systems” - White Chapter 5

Online Resources


Testing Strategy

Verification Steps

  1. Binary Structure Check: ```bash

    Verify vector table is at correct address

    arm-none-eabi-nm blink.elf | grep -E “vectors|reset”

Verify sizes

arm-none-eabi-size blink.elf

text should be small (<1KB)

data should be tiny

bss depends on your variables


2. **Visual Verification**:
   - LED should blink visibly (~1Hz)
   - If too fast/slow, adjust delay value
   - If no blink, LED might be stuck on or off

3. **Debug with OpenOCD + GDB**:
```bash
# Terminal 1: Start OpenOCD
openocd -f interface/stlink.cfg -f target/stm32f4x.cfg

# Terminal 2: Connect GDB
arm-none-eabi-gdb blink.elf
(gdb) target remote :3333
(gdb) monitor reset halt
(gdb) break main
(gdb) continue
(gdb) info registers
(gdb) x/10x 0x40020014  # Examine GPIO ODR
(gdb) stepi             # Single step

Test Cases

Test Expected Result Verification
Power on LED starts blinking Visual
Reset button Blink restarts Visual
Change delay Blink rate changes Rebuild, reflash
Check MODER Bits 11:10 = 01 GDB: x/x &GPIOA->MODER
Check ODR Bit 5 toggles GDB: watch 0x40020014

Common Pitfalls & Debugging

Problem Symptom Root Cause Fix
No blink, LED off Nothing happens GPIO clock not enabled Check RCC->AHB1ENR
LED stuck on Constant light MODER wrong or no toggle Verify MODER bits
Immediate HardFault Crashes on boot Vector table wrong Check alignment, addresses
delay() optimized away Blinks too fast Compiler removed loop Use volatile counter
Can’t flash Programming fails Protection bits set Full chip erase
Wrong LED pin Different LED blinks Pin number wrong Check schematic (PA5 for Nucleo)

Debugging Techniques

/* Add a "sign of life" check */
void fault_handler(void) {
    /* If we get here, something's very wrong */
    /* Fast blink = fault indicator */
    while (1) {
        GPIOA->ODR ^= (1 << LED_PIN);
        for (volatile int i = 0; i < 100000; i++);
    }
}

/* Check if clock is actually enabled */
volatile uint32_t rcc_val = RCC->AHB1ENR;
/* Read it back after setting - compiler can't optimize away */

Extensions & Challenges

After Basic Completion

  1. Configure the PLL: Get 168MHz instead of default 16MHz
  2. Use SysTick: More accurate timing than busy loops
  3. Add button input: Read PC13, toggle blink on press
  4. Multiple patterns: SOS in Morse code, heartbeat
  5. Add UART output: See Project 4

Challenge Mode

  • Implement a basic scheduler (blink + button polling)
  • Drive multiple LEDs with PWM brightness control
  • Port to Raspberry Pi bare-metal
  • Make binary as small as possible (<256 bytes?)

Advanced: SysTick Delay

/* SysTick registers */
#define STK_CTRL   (*(volatile uint32_t *)0xE000E010)
#define STK_LOAD   (*(volatile uint32_t *)0xE000E014)
#define STK_VAL    (*(volatile uint32_t *)0xE000E018)

#define STK_CTRL_ENABLE    (1 << 0)
#define STK_CTRL_CLKSOURCE (1 << 2)

void systick_delay_ms(uint32_t ms) {
    /* Assuming 16MHz clock */
    STK_LOAD = 16000 - 1;  /* 1ms at 16MHz */
    STK_VAL = 0;
    STK_CTRL = STK_CTRL_ENABLE | STK_CTRL_CLKSOURCE;

    for (uint32_t i = 0; i < ms; i++) {
        while (!(STK_CTRL & (1 << 16)));  /* Wait for COUNTFLAG */
    }

    STK_CTRL = 0;
}

Self-Assessment Checklist

Before moving to Project 4, verify you can:

  • Explain what happens from power-on to main()
  • Write a vector table from memory
  • Create a linker script for a given memory map
  • Enable a GPIO peripheral clock
  • Configure a pin as output using MODER
  • Explain why volatile is necessary for hardware registers
  • Debug with GDB and examine memory-mapped registers
  • Calculate rough delay loop iterations for a given clock

Final Test

Given a new ARM chip datasheet with:

  • Flash at 0x00000000, 64KB
  • RAM at 0x20000000, 16KB
  • GPIOB at 0x40010400
  • RCC at 0x40021000

Write from scratch (no copy-paste):

  1. Vector table
  2. Linker script
  3. Code to blink GPIOB pin 7

If you can do this, you’re ready for UART!


Learning Milestones

Track your progress through these milestones:

Milestone You Can… Understanding Level
1 Code compiles with arm-none-eabi-gcc You understand cross-compilation
2 Flash binary and CPU doesn’t crash Vector table is correct
3 LED lights up (even if stuck) GPIO configuration works
4 LED blinks at approximately correct rate You understand timing without OS

<- Previous Project: ARM Assembly Calculator Next Project: UART Driver ->