Add STM32F0 firmware

master
fruchti 2017-01-20 22:20:00 +01:00
parent e2baca5c35
commit 87536ad9f8
14 changed files with 718 additions and 0 deletions

2
stm32f030f4p6/.gitignore vendored Normal file
View File

@ -0,0 +1,2 @@
build/*
src/.local.vimrc

View File

@ -0,0 +1 @@
233

7
stm32f030f4p6/flash.cfg Normal file
View File

@ -0,0 +1,7 @@
source [find interface/stlink-v2.cfg]
transport select "hla_swd"
source [find target/stm32f0x.cfg]
reset_config trst_and_srst
init
arm semihosting enable
reset run

6
stm32f030f4p6/flash.gdb Normal file
View File

@ -0,0 +1,6 @@
target remote :3333
file build/main.elf
monitor reset halt
monitor flash write_image erase build/main.bin 0x8000000
#load build/main.elf
monitor reset run

View File

@ -0,0 +1,163 @@
/*
*****************************************************************************
**
** File : STM32F030F4_FLASH.ld
**
** Abstract : Linker script for STM32F030F4 Device with
** 16KByte FLASH, 4KByte RAM
**
** Set heap size, stack size and stack location according
** to application requirements.
**
** Set memory bank area and size if external memory is used.
**
** Target : STMicroelectronics STM32
**
*****************************************************************************
*/
/* Entry Point */
ENTRY(Reset_Handler)
/* Highest address of the user mode stack */
_estack = 0x20001000; /* end of 4K RAM */
/* Generate a link error if heap and stack don't fit into RAM */
_Min_Heap_Size = 0; /* required amount of heap */
_Min_Stack_Size = 0x80; /* required amount of stack */
/* Specify the memory areas */
MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 4K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}
/* Define output sections */
SECTIONS
{
/* The startup code goes first into FLASH */
.isr_vector :
{
. = ALIGN(4);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >FLASH
/* The program code and other data goes into FLASH */
.text :
{
. = ALIGN(4);
*(.text) /* .text sections (code) */
*(.text*) /* .text* sections (code) */
*(.glue_7) /* glue arm to thumb code */
*(.glue_7t) /* glue thumb to arm code */
*(.eh_frame)
KEEP (*(.init))
KEEP (*(.fini))
. = ALIGN(4);
_etext = .; /* define a global symbols at end of code */
} >FLASH
/* Constant data goes into FLASH */
.rodata :
{
. = ALIGN(4);
*(.rodata) /* .rodata sections (constants, strings, etc.) */
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
. = ALIGN(4);
} >FLASH
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
.ARM : {
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
} >FLASH
.preinit_array :
{
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array*))
PROVIDE_HIDDEN (__preinit_array_end = .);
} >FLASH
.init_array :
{
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array*))
PROVIDE_HIDDEN (__init_array_end = .);
} >FLASH
.fini_array :
{
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(SORT(.fini_array.*)))
KEEP (*(.fini_array*))
PROVIDE_HIDDEN (__fini_array_end = .);
} >FLASH
/* used by the startup to initialize data */
_sidata = LOADADDR(.data);
/* Initialized data sections goes into RAM, load LMA copy after code */
.data :
{
. = ALIGN(4);
_sdata = .; /* create a global symbol at data start */
*(.data) /* .data sections */
*(.data*) /* .data* sections */
. = ALIGN(4);
_edata = .; /* define a global symbol at data end */
} >RAM AT> FLASH
/* Uninitialized data section */
. = ALIGN(4);
.bss :
{
/* This is used by the startup in order to initialize the .bss secion */
_sbss = .; /* define a global symbol at bss start */
__bss_start__ = _sbss;
*(.bss)
*(.bss*)
*(COMMON)
. = ALIGN(4);
_ebss = .; /* define a global symbol at bss end */
__bss_end__ = _ebss;
} >RAM
/* User_heap_stack section, used to check that there is enough RAM left */
._user_heap_stack :
{
. = ALIGN(4);
PROVIDE ( end = . );
PROVIDE ( _end = . );
. = . + _Min_Heap_Size;
. = . + _Min_Stack_Size;
. = ALIGN(4);
} >RAM
/* MEMORY_bank1 section, code must be located here explicitly */
/* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */
.memory_b1_text :
{
*(.mb1text) /* .mb1text sections (code) */
*(.mb1text*) /* .mb1text* sections (code) */
*(.mb1rodata) /* read-only data (constants) */
*(.mb1rodata*)
} >MEMORY_B1
/* Remove information from the standard libraries */
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
}
.ARM.attributes 0 : { *(.ARM.attributes) }
}

View File

@ -0,0 +1,165 @@
/*
*****************************************************************************
**
** File : STM32F030F4_FLASH.ld
**
** Abstract : Linker script for STM32F030F4 Device with
** 16KByte FLASH, 4KByte RAM
**
** Set heap size, stack size and stack location according
** to application requirements.
**
** Set memory bank area and size if external memory is used.
**
** Target : STMicroelectronics STM32
**
*****************************************************************************
*/
/* Entry Point */
ENTRY(Reset_Handler)
/* Highest address of the user mode stack */
_estack = 0x20001000; /* end of 4K RAM */
/* Generate a link error if heap and stack don't fit into RAM */
_Min_Heap_Size = 0; /* required amount of heap */
_Min_Stack_Size = 0x80; /* required amount of stack */
/* Specify the memory areas */
MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 8K
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 4K
MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K
}
/* Define output sections */
SECTIONS
{
/* The startup code goes first into FLASH */
.isr_vector :
{
. = ALIGN(4);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >FLASH
/* The program code and other data goes into FLASH */
.text :
{
. = ALIGN(4);
*(.text) /* .text sections (code) */
*(.text*) /* .text* sections (code) */
*(.glue_7) /* glue arm to thumb code */
*(.glue_7t) /* glue thumb to arm code */
*(.eh_frame)
KEEP (*(.init))
KEEP (*(.fini))
. = ALIGN(4);
_etext = .; /* define a global symbols at end of code */
} >FLASH
/* Constant data goes into FLASH */
.rodata :
{
. = ALIGN(4);
*(.rodata) /* .rodata sections (constants, strings, etc.) */
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
. = ALIGN(4);
} >FLASH
.ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH
.ARM : {
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
} >FLASH
.preinit_array :
{
PROVIDE_HIDDEN (__preinit_array_start = .);
KEEP (*(.preinit_array*))
PROVIDE_HIDDEN (__preinit_array_end = .);
} >FLASH
.init_array :
{
PROVIDE_HIDDEN (__init_array_start = .);
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array*))
PROVIDE_HIDDEN (__init_array_end = .);
} >FLASH
.fini_array :
{
PROVIDE_HIDDEN (__fini_array_start = .);
KEEP (*(SORT(.fini_array.*)))
KEEP (*(.fini_array*))
PROVIDE_HIDDEN (__fini_array_end = .);
} >FLASH
/* used by the startup to initialize data */
_sidata = LOADADDR(.data);
/* Initialized data sections goes into RAM, load LMA copy after code */
.data :
{
. = ALIGN(4);
_sdata = .; /* create a global symbol at data start */
*(.data) /* .data sections */
*(.data*) /* .data* sections */
. = ALIGN(4);
*(.ramfunctions)
_edata = .; /* define a global symbol at data end */
} >RAM AT> FLASH
/* Uninitialized data section */
. = ALIGN(4);
.bss :
{
/* This is used by the startup in order to initialize the .bss secion */
_sbss = .; /* define a global symbol at bss start */
__bss_start__ = _sbss;
*(.bss)
*(.bss*)
*(COMMON)
. = ALIGN(4);
_ebss = .; /* define a global symbol at bss end */
__bss_end__ = _ebss;
} >RAM
/* User_heap_stack section, used to check that there is enough RAM left */
._user_heap_stack :
{
. = ALIGN(4);
PROVIDE ( end = . );
PROVIDE ( _end = . );
. = . + _Min_Heap_Size;
. = . + _Min_Stack_Size;
. = ALIGN(4);
} >RAM
/* MEMORY_bank1 section, code must be located here explicitly */
/* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */
.memory_b1_text :
{
*(.mb1text) /* .mb1text sections (code) */
*(.mb1text*) /* .mb1text* sections (code) */
*(.mb1rodata) /* read-only data (constants) */
*(.mb1rodata*)
} >MEMORY_B1
/* Remove information from the standard libraries */
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
}
.ARM.attributes 0 : { *(.ARM.attributes) }
}

100
stm32f030f4p6/makefile Normal file
View File

@ -0,0 +1,100 @@
PROJECT = main
LOCAL_SOURCE_DIR = src
LOCAL_LIBS =
BUILD_DIR = build
CUBE_DIR := /opt/stm32cube/STM32Cube_FW_F0_V1.6.0
DEBUG := no
CUBE_DEVICE = STM32F0xx
H_DEVICE = STM32F030x6
STARTUP_SOURCE_DIR = $(CUBE_DIR)/Drivers/CMSIS/Device/ST/$(CUBE_DEVICE)/Source/Templates/gcc
LOCAL_SOURCES = $(wildcard $(LOCAL_SOURCE_DIR)/*.c)
LOCAL_LIB_SOURCES = $(foreach dir,$(LOCAL_LIBS),$(wildcard $(dir)/*.c))
STARTUP_SOURCES = $(STARTUP_SOURCE_DIR)/startup_stm32f030x6.s
ifeq ($(DEBUG),yes)
DEBUG_FLAGS = -DDEBUG -g3
endif
BUILD_NUMBER_FILE = build-number.txt
BUILD_ID_FLAGS = -Xlinker --defsym -Xlinker __BUILD_DATE=$$(date +'%Y%m%d') \
-Xlinker --defsym -Xlinker __BUILD_NUMBER=$$(cat $(BUILD_NUMBER_FILE))
CURRENT_BUILD_CONFIG := $(shell cat makefile | md5sum) DEBUG = $(DEBUG) CUBE_DIR = $(CUBE_DIR)
LAST_BUILD_CONFIG := $(shell cat $(BUILD_DIR)/build-config.txt)
CFLAGS = -mcpu=cortex-m0 -mlittle-endian -mthumb -mthumb-interwork -mfloat-abi=soft -Os \
-fmessage-length=0 -fsigned-char -ffunction-sections -fdata-sections -mlong-calls \
-Wall -Xlinker --gc-sections -I$(CUBE_DIR)/Drivers/CMSIS/Include \
-I$(CUBE_DIR)/Drivers/CMSIS/Device/ST/$(CUBE_DEVICE)/Include -D$(H_DEVICE) \
-Tld/stm32f030f4_flash.ld -Wl,-Map=$(BUILD_DIR)/$(PROJECT).map -std=c99 \
$(addprefix -I,$(LOCAL_LIBS)) $(DEBUG_FLAGS)
RM = rm -f
CC = arm-none-eabi-gcc
OBJCOPY = arm-none-eabi-objcopy
SIZE = arm-none-eabi-size
OBJDUMP = arm-none-eabi-objdump
LOCAL_OBJECTS = $(patsubst $(LOCAL_SOURCE_DIR)/%.c, $(BUILD_DIR)/%.o, $(LOCAL_SOURCES))
LOCAL_LIB_OBJECTS = $(addprefix $(BUILD_DIR)/,$(addsuffix .o,$(basename $(notdir $(LOCAL_LIB_SOURCES)))))
STARTUP_OBJECTS = $(patsubst $(STARTUP_SOURCE_DIR)/%.s, $(BUILD_DIR)/%.o, $(STARTUP_SOURCES))
OBJECTS = $(LOCAL_OBJECTS) $(LOCAL_LIB_OBJECTS) $(STARTUP_OBJECTS)
LOCAL_DEPENDS = $(patsubst $(LOCAL_SOURCE_DIR)/%.c, $(BUILD_DIR)/%.d, $(LOCAL_SOURCES))
.DEFAULT_GOAL = all
.DELETE_ON_ERROR:
$(LOCAL_OBJECTS): $(BUILD_DIR)/%.o: $(LOCAL_SOURCE_DIR)/%.c
$(CC) $< -c -o $@ $(CFLAGS)
define define_lib_compile_rules
$(LOCAL_LIB_OBJECTS): $(BUILD_DIR)/%.o: $(1)/%.c
$$(CC) $$(CFLAGS) -o $$@ -c $$<
endef
$(foreach directory,$(LOCAL_LIBS),$(eval $(call define_lib_compile_rules,$(directory))))
$(STARTUP_OBJECTS): $(BUILD_DIR)/%.o: $(STARTUP_SOURCE_DIR)/%.s
$(CC) $< -c -o $@ $(CFLAGS)
$(LOCAL_DEPENDS): $(BUILD_DIR)/%.d: $(LOCAL_SOURCE_DIR)/%.c
@set -e; rm -f $@; $(CC) -MM $(CFLAGS) $< > $@.$$$$; sed 's,\($*\)\.o[ :]*,build\/\1.o $@ : ,g' < $@.$$$$ > $@; rm -f $@.$$$$
include $(LOCAL_DEPENDS)
$(BUILD_DIR)/$(PROJECT).elf: $(OBJECTS) $(BUILD_NUMBER_FILE)
$(CC) $(OBJECTS) $(CFLAGS) $(BUILD_ID_FLAGS) -o $@
$(BUILD_DIR)/$(PROJECT).bin: $(BUILD_DIR)/$(PROJECT).elf
$(OBJCOPY) -O binary -S $< $@
$(BUILD_DIR):
if [ ! -d "$(BUILD_DIR)" ]; then mkdir "$(BUILD_DIR)"; fi
$(BUILD_NUMBER_FILE): $(OBJECTS)
@if ! test -f $(BUILD_NUMBER_FILE); then echo 0 > $(BUILD_NUMBER_FILE); else \
echo $$(($$(cat $(BUILD_NUMBER_FILE)) + 1)) > $(BUILD_NUMBER_FILE) ; fi
# Rebuild everything in case of a makefile/configuration change
.PHONY: all
ifneq ("$(CURRENT_BUILD_CONFIG)","$(LAST_BUILD_CONFIG)")
all: clean incrementalbuild
else
all: incrementalbuild
endif
.PHONY: incrementalbuild
incrementalbuild: $(BUILD_DIR) $(OBJECTS) $(BUILD_DIR)/$(PROJECT).elf $(BUILD_DIR)/$(PROJECT).bin
$(SIZE) $(BUILD_DIR)/$(PROJECT).elf
@echo "$(CURRENT_BUILD_CONFIG)" > $(BUILD_DIR)/build-config.txt
.PHONY: program
program: $(BUILD_DIR)/$(PROJECT).bin
if ps -e | grep openocd ; then arm-none-eabi-gdb -batch -x flash.gdb ; else st-flash --reset write $(BUILD_DIR)/$(PROJECT).bin 0x8000000 ; fi
.PHONY: clean
clean:
$(RM) $(BUILD_DIR)/*

View File

@ -0,0 +1,10 @@
#ifndef BUILDID_H_
#define BUILDID_H_
extern char __BUILD_DATE;
extern char __BUILD_NUMBER;
#define BUILD_DATE ((uint32_t)&__BUILD_DATE)
#define BUILD_NUMBER ((uint32_t)&__BUILD_NUMBER)
#endif

125
stm32f030f4p6/src/main.c Normal file
View File

@ -0,0 +1,125 @@
#include "main.h"
#define SCARCITY 900
volatile uint16_t ADC_Reading;
int main(void)
{
RCC->AHBENR |= RCC_AHBENR_GPIOAEN;
RCC->AHBENR |= RCC_AHBENR_GPIOBEN;
RCC->AHBENR |= RCC_AHBENR_GPIOFEN;
RCC->APB1ENR |= RCC_APB1ENR_TIM14EN;
GPIOA->PUPDR |= (1 << (PIN_DIP_1 << 1)) | (1 << (PIN_DIP_2 << 1)) | (1 << (PIN_DIP_3 << 1)) | (1 << (PIN_DIP_4 << 1));
LED_Init();
ADC_Init();
for(int i = 0; i < LED_COUNT; i++)
{
}
TIM14->PSC = 10000;
TIM14->ARR = 100;
TIM14->CNT = 0;
TIM14->DIER = TIM_DIER_UIE;
NVIC_EnableIRQ(TIM14_IRQn);
TIM14->CR1 = TIM_CR1_ARPE | TIM_CR1_CEN;
for(;;);
return 0;
}
void ADC_Init(void)
{
RCC->APB2ENR |= RCC_APB2ENR_ADCEN;
ADC1->CFGR1 = ADC_CFGR1_CONT | ADC_CFGR1_OVRMOD;
ADC1->SMPR = 1;
ADC1->CHSELR = ADC_CHSELR_CHSEL0;
// // ADC Calibration
// ADC1->CR |= ADC_CR_ADDIS;
// while(ADC1->CR & ADC_CR_ADEN);
// ADC1->CR |= ADC_CR_ADCAL;
// while(ADC1->CR & ADC_CR_ADCAL);
// Enable interrupt
ADC1->IER = ADC_IER_EOCIE;
NVIC_EnableIRQ(ADC1_IRQn);
// Enable the ADC
ADC1->CR |= ADC_CR_ADEN;
while(~ADC1->ISR & ADC_ISR_ADRDY);
// GPIO configuration
GPIOA->MODER |= (3 << (PIN_SENSOR << 1));
GPIOA->PUPDR |= (1 << (PIN_SENSOR << 1));
// And start the first conversion
ADC1->CR |= ADC_CR_ADSTART;
}
bool IsOn(void)
{
// Always on?
if(~GPIOA->IDR & (1 << PIN_DIP_1))
return true;
// No -> check if it's dark
return ADC_Reading > 240;
}
uint32_t GetFactor(void)
{
uint8_t setting = 0;
if(~GPIOA->IDR & (1 << PIN_DIP_4))
setting |= 1;
if(~GPIOA->IDR & (1 << PIN_DIP_3))
setting |= 2;
if(~GPIOA->IDR & (1 << PIN_DIP_2))
setting |= 4;
return 1 << setting;
}
void TIM14_IRQHandler(void)
{
if(TIM14->SR & TIM_SR_UIF)
{
uint32_t threshold = RAND_MAX / LED_COUNT / SCARCITY * GetFactor();
if(!IsOn())
threshold = 0;
for(unsigned int i = 0; i < LED_COUNT; i++)
{
if(rand() < threshold)
LED_Buffer[i].R = 255;
else
LED_Buffer[i].R = 0;
if(rand() < threshold)
LED_Buffer[i].G = 255;
else
LED_Buffer[i].G = 0;
if(rand() < threshold)
LED_Buffer[i].B = 255;
else
LED_Buffer[i].B = 0;
}
LED_Refresh();
TIM14->SR &= ~TIM_SR_UIF;
}
NVIC_ClearPendingIRQ(TIM14_IRQn);
}
void ADC1_IRQHandler(void)
{
ADC_Reading = ADC1->DR;
ADC1->ISR |= ADC_ISR_EOC;
NVIC_ClearPendingIRQ(ADC1_IRQn);
}

17
stm32f030f4p6/src/main.h Normal file
View File

@ -0,0 +1,17 @@
#ifndef MAIN_H_
#define MAIN_H_
#include <stdlib.h>
#include <stdbool.h>
#include "stm32f030x6.h"
#include "pinning.h"
#include "buildid.h"
#include "ws2812b_spi.h"
int main(void);
void ADC_Init(void);
void TIM14_IRQHandler(void);
void ADC1_IRQHandler(void);
#endif

View File

@ -0,0 +1,10 @@
#ifndef PINNING_H_
#define PINNING_H_
#define PIN_SENSOR 0 // PA0 - light sensor
#define PIN_DIP_1 4 // PA1 - DIP switch 1
#define PIN_DIP_2 3 // PA2 - DIP switch 2
#define PIN_DIP_3 2 // PA3 - DIP switch 3
#define PIN_DIP_4 1 // PA4 - DIP switch 4
#endif

View File

@ -0,0 +1,23 @@
#include <stdint.h>
#include "stm32f030x6.h"
void SystemInit(void)
{
// Activate HSI and wait for it to be ready
RCC->CR = RCC_CR_HSION;
while(!(RCC->CR & RCC_CR_HSIRDY));
// Set PLL to x10 (-> 40MHz system clock)
RCC->CFGR = RCC_CFGR_PLLMUL_3;
// Activate PLL and wait
RCC->CR |= RCC_CR_PLLON;
while(!(RCC->CR & RCC_CR_PLLRDY));
// Select PLL as clock source
RCC->CFGR |= RCC_CFGR_SW_1;
// Disable all interrupts
RCC->CIR = 0x00000000;
}

View File

@ -0,0 +1,58 @@
#include "ws2812b_spi.h"
volatile LED_Color_t LED_Buffer[LED_COUNT];
volatile uint8_t LED_DMABuffer[LED_DMA_BYTES + 1];
#ifndef LED_INVERT_DO
const static uint8_t LED_PatternTable[4] = {0b100100, 0b100110, 0b110100, 0b110110};
#else
const static uint8_t LED_PatternTable[4] = {0b011011, 0b011001, 0b001011, 0b001001};
#endif
void LED_Init(void)
{
RCC->AHBENR |= RCC_AHBENR_GPIOAEN;
RCC->AHBENR |= RCC_AHBENR_DMAEN;
RCC->APB2ENR |= RCC_APB2ENR_SPI1EN;
// GPIO initialisation
GPIOA->MODER |= (2 << (LED_PIN_DO << 1));
// SPI initialisation
SPI1->CR1 = SPI_CR1_BIDIMODE | SPI_CR1_BIDIOE |\
SPI_CR1_BR_1 | SPI_CR1_BR_0 | SPI_CR1_MSTR;
SPI1->CR2 = SPI_CR2_DS_2 | SPI_CR2_DS_0 | SPI_CR2_FRF;
// DMA configuration (DMA channel 3 is used)
DMA1_Channel3->CCR = DMA_CCR_PL_1 | DMA_CCR_MINC | DMA_CCR_DIR;
DMA1_Channel3->CPAR = (uint32_t)(&SPI1->DR);
SPI1->CR2 |= SPI_CR2_TXDMAEN;
// Enable SPI
SPI1->CR1 |= SPI_CR1_SPE;
}
static inline void LED_StartDMA(void)
{
DMA1_Channel3->CCR &= ~DMA_CCR_EN;
DMA1_Channel3->CNDTR = LED_DMA_BYTES + 1;
DMA1_Channel3->CMAR = (uint32_t)(&LED_DMABuffer);
DMA1_Channel3->CCR |= DMA_CCR_EN;
}
void LED_Refresh(void)
{
for(unsigned int i = 0; i < LED_DMA_BYTES; i++)
{
unsigned int byteindex = i / 4;
uint8_t bitindex = 6 - (i - 4 * byteindex) * 2;
uint8_t bitmask = 3 << bitindex;
uint8_t *byte = (uint8_t*)LED_Buffer + byteindex;
LED_DMABuffer[i + 1] = LED_PatternTable[(*byte & bitmask) >> bitindex];
}
#ifdef LED_INVERT_DO
LED_DMABuffer[0] = 0xff;
#else
LED_DMABuffer[0] = 0;
#endif
LED_StartDMA();
}

View File

@ -0,0 +1,31 @@
#ifndef WS2812B_SPI_H
#define WS2812B_SPI_H
#include "stm32f030x6.h"
#include "pinning.h"
// The WS2812B data line has to be connected to PA7 (SPI MOSI). Unfortunately,
// there is only one SPI interface, so this library cannot be used together with
// an SD card.
#define LED_PIN_DO 7
// The number of LEDs daisy-chained
#define LED_COUNT 120
// Invert the output (if a transistor is used for level-shifting)
#define LED_INVERT_DO
#define LED_DMA_BYTES (LED_COUNT * 3 * 4)
typedef struct
{
uint8_t G, R, B;
} LED_Color_t;
extern volatile LED_Color_t LED_Buffer[LED_COUNT];
void LED_Init(void);
void LED_Refresh(void);
#endif