started stm32-f103rb-nucleo port

This commit is contained in:
matthias.ringwald@gmail.com 2014-09-28 20:48:04 +00:00
parent 23bed257d1
commit 7bb5609e0a
8 changed files with 573 additions and 0 deletions

View File

@ -0,0 +1,38 @@
#
# Makefile for STM32-F103RB Nucleo board with CC256x Bluetooth modules
#
BINARY=led_counter
OPENCM3_DIR = libopencm3
LDSCRIPT = stm32f1-nucleo.ld
BTSTACK_ROOT = ../..
CORE = \
main.c \
${BTSTACK_ROOT}/src/btstack_memory.c \
${BTSTACK_ROOT}/src/linked_list.c \
${BTSTACK_ROOT}/src/memory_pool.c \
${BTSTACK_ROOT}/src/run_loop.c \
${BTSTACK_ROOT}/src/run_loop_embedded.c
CORE_OBJ = $(CORE:.c=.o)
OBJS += $(CORE_OBJ)
CFLAGS = -I. -I$(BTSTACK_ROOT)/include -I$(BTSTACK_ROOT)/src
examples: libopencm3/lib/libopencm3_stm32f1.a led_counter.elf
include libopencm3.stm32f1.mk
clean:
rm -f *.map *.o *.d *.out *.elf *.bin *.hex ../driver/*.o ../../src/*.o ../src/*.o ../firmware/*.o ${BTSTACK_ROOT}/chipset-cc256x/*.o ${BTSTACK_ROOT}/src/*.o
# git clone and compile libopencm3
libopencm3/lib/libopencm3_stm32f1.a:
git clone git@github.com:libopencm3/libopencm3.git
make -C libopencm3
my_flash: $(BINARY).bin
st-flash write $(BINARY).bin 0x8000000

View File

@ -0,0 +1,20 @@
BTstack port for STM32 F103RB Nucleo board and CC256x Bluetooth chipset
based on GNU Tools for ARM Embedded Processors and libopencm3
GNU Tools for ARM Embedded Processors:
https://launchpad.net/gcc-arm-embedded
libopencm3 is automatically build from its git repository
Configuration:
- LED on PA5
- Debug UART: USART2 - 9600/8/N/1, TX on PA2
- Bluetooth: USART3 with Hardware Flowcontrol. TX PB10, RX PB11, CTS PB13 (in), RTS PB14 (out), N_SHUTDOWN PB15
TODO:
- figure out how to compile multiple examples with single Makefile/folder
- implement hal_uart_dma.h
- implement hal_cpu.h
- create and implement hal_led.h
- extract classic and le examples into example/embedded
- use examples from BTSTACK_ROOT/example/embedded directly

View File

@ -0,0 +1,26 @@
#define EMBEDDED
#define HAVE_INIT_SCRIPT
#define HAVE_BZERO
#define HAVE_TICK
#define HAVE_EHCILL
//#define ENABLE_LOG_INFO
// #define ENABLE_LOG_ERROR
#define HCI_ACL_PAYLOAD_SIZE 52
//
#define MAX_SPP_CONNECTIONS 1
#define MAX_NO_HCI_CONNECTIONS MAX_SPP_CONNECTIONS
#define MAX_NO_L2CAP_SERVICES 2
#define MAX_NO_L2CAP_CHANNELS (1+MAX_SPP_CONNECTIONS)
#define MAX_NO_RFCOMM_MULTIPLEXERS MAX_SPP_CONNECTIONS
#define MAX_NO_RFCOMM_SERVICES 1
#define MAX_NO_RFCOMM_CHANNELS MAX_SPP_CONNECTIONS
#define MAX_NO_DB_MEM_DEVICE_LINK_KEYS 2
#define MAX_NO_DB_MEM_DEVICE_NAMES 0
#define MAX_NO_DB_MEM_SERVICES 1

View File

@ -0,0 +1,58 @@
//*****************************************************************************
//
// led_counter demo - uses the BTstack run loop to blink an LED
//
//*****************************************************************************
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include "btstack_memory.h"
#include <btstack/run_loop.h>
#include "btstack-config.h"
#define HEARTBEAT_PERIOD_MS 1000
static int counter = 0;
static timer_source_t heartbeat;
static void register_timer(timer_source_t *timer, uint16_t period){
run_loop_set_timer(timer, period);
run_loop_add_timer(timer);
}
static void heartbeat_handler(timer_source_t *ts){
// increment counter
char lineBuffer[30];
sprintf(lineBuffer, "BTstack counter %04u\n", ++counter);
printf(lineBuffer);
// toggle LED
// LED_PORT_OUT = LED_PORT_OUT ^ LED_2;
// re-register timer
register_timer(ts, HEARTBEAT_PERIOD_MS);
}
// main
int btstack_main(void)
{
/// GET STARTED with BTstack ///
btstack_memory_init();
run_loop_init(RUN_LOOP_EMBEDDED);
// set one-shot timer
heartbeat.process = &heartbeat_handler;
register_timer(&heartbeat, HEARTBEAT_PERIOD_MS);
printf("Run...\n\r");
// go!
run_loop_execute();
return 0;
}

View File

@ -0,0 +1,239 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
## Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
## Copyright (C) 2013 Frantisek Burian <BuFran@seznam.cz>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
# Be silent per default, but 'make V=1' will show all compiler calls.
ifneq ($(V),1)
Q := @
NULL := 2>/dev/null
endif
###############################################################################
# Executables
PREFIX ?= arm-none-eabi
CC := $(PREFIX)-gcc
CXX := $(PREFIX)-g++
LD := $(PREFIX)-gcc
AR := $(PREFIX)-ar
AS := $(PREFIX)-as
OBJCOPY := $(PREFIX)-objcopy
OBJDUMP := $(PREFIX)-objdump
GDB := $(PREFIX)-gdb
STFLASH = $(shell which st-flash)
STYLECHECK := /checkpatch.pl
STYLECHECKFLAGS := --no-tree -f --terse --mailback
STYLECHECKFILES := $(shell find . -name '*.[ch]')
###############################################################################
# Source files
LDSCRIPT ?= $(BINARY).ld
OBJS += $(BINARY).o
ifeq ($(strip $(OPENCM3_DIR)),)
# user has not specified the library path, so we try to detect it
# where we search for the library
LIBPATHS := ./libopencm3 ../../../../libopencm3 ../../../../../libopencm3
OPENCM3_DIR := $(wildcard $(LIBPATHS:=/locm3.sublime-project))
OPENCM3_DIR := $(firstword $(dir $(OPENCM3_DIR)))
ifeq ($(strip $(OPENCM3_DIR)),)
$(warning Cannot find libopencm3 library in the standard search paths.)
$(error Please specify it through OPENCM3_DIR variable!)
endif
endif
ifeq ($(V),1)
$(info Using $(OPENCM3_DIR) path to library)
endif
INCLUDE_DIR = $(OPENCM3_DIR)/include
LIB_DIR = $(OPENCM3_DIR)/lib
SCRIPT_DIR = $(OPENCM3_DIR)/scripts
###############################################################################
# C flags
CFLAGS += -Os -g
CFLAGS += -Wextra -Wshadow -Wimplicit-function-declaration
CFLAGS += -Wredundant-decls -Wmissing-prototypes -Wstrict-prototypes
CFLAGS += -fno-common -ffunction-sections -fdata-sections
###############################################################################
# C++ flags
CXXFLAGS += -Os -g
CXXFLAGS += -Wextra -Wshadow -Wredundant-decls -Weffc++
CXXFLAGS += -fno-common -ffunction-sections -fdata-sections
###############################################################################
# C & C++ preprocessor common flags
CPPFLAGS += -MD
CPPFLAGS += -Wall -Wundef
CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS)
###############################################################################
# Linker flags
LDFLAGS += --static -nostartfiles
LDFLAGS += -L$(LIB_DIR)
LDFLAGS += -T$(LDSCRIPT)
LDFLAGS += -Wl,-Map=$(*).map
LDFLAGS += -Wl,--gc-sections
ifeq ($(V),1)
LDFLAGS += -Wl,--print-gc-sections
endif
###############################################################################
# Used libraries
LDLIBS += -l$(LIBNAME)
LDLIBS += -Wl,--start-group -lc -lgcc -lnosys -Wl,--end-group
###############################################################################
###############################################################################
###############################################################################
.SUFFIXES: .elf .bin .hex .srec .list .map .images
.SECONDEXPANSION:
.SECONDARY:
all: elf
elf: $(BINARY).elf
bin: $(BINARY).bin
hex: $(BINARY).hex
srec: $(BINARY).srec
list: $(BINARY).list
images: $(BINARY).images
flash: $(BINARY).flash
%.images: %.bin %.hex %.srec %.list %.map
@#printf "*** $* images generated ***\n"
%.bin: %.elf
@#printf " OBJCOPY $(*).bin\n"
$(Q)$(OBJCOPY) -Obinary $(*).elf $(*).bin
%.hex: %.elf
@#printf " OBJCOPY $(*).hex\n"
$(Q)$(OBJCOPY) -Oihex $(*).elf $(*).hex
%.srec: %.elf
@#printf " OBJCOPY $(*).srec\n"
$(Q)$(OBJCOPY) -Osrec $(*).elf $(*).srec
%.list: %.elf
@#printf " OBJDUMP $(*).list\n"
$(Q)$(OBJDUMP) -S $(*).elf > $(*).list
%.elf %.map: $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a
@#printf " LD $(*).elf\n"
$(Q)$(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(*).elf
%.o: %.c
@#printf " CC $(*).c\n"
$(Q)$(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $(*).o -c $(*).c
%.o: %.cxx
@#printf " CXX $(*).cxx\n"
$(Q)$(CXX) $(CXXFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $(*).o -c $(*).cxx
%.o: %.cpp
@#printf " CXX $(*).cpp\n"
$(Q)$(CXX) $(CXXFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $(*).o -c $(*).cpp
# clean:
# @#printf " CLEAN\n"
# $(Q)$(RM) *.o *.d *.elf *.bin *.hex *.srec *.list *.map
stylecheck: $(STYLECHECKFILES:=.stylecheck)
styleclean: $(STYLECHECKFILES:=.styleclean)
# the cat is due to multithreaded nature - we like to have consistent chunks of text on the output
%.stylecheck: %
$(Q)$(SCRIPT_DIR)$(STYLECHECK) $(STYLECHECKFLAGS) $* > $*.stylecheck; \
if [ -s $*.stylecheck ]; then \
cat $*.stylecheck; \
else \
rm -f $*.stylecheck; \
fi;
%.styleclean:
$(Q)rm -f $*.stylecheck;
%.stlink-flash: %.bin
@printf " FLASH $<\n"
$(Q)$(STFLASH) write $(*).bin 0x8000000
ifeq ($(STLINK_PORT),)
ifeq ($(BMP_PORT),)
ifeq ($(OOCD_SERIAL),)
%.flash: %.hex
@printf " FLASH $<\n"
@# IMPORTANT: Don't use "resume", only "reset" will work correctly!
$(Q)$(OOCD) -f interface/$(OOCD_INTERFACE).cfg \
-f board/$(OOCD_BOARD).cfg \
-c "init" -c "reset init" \
-c "flash write_image erase $(*).hex" \
-c "reset" \
-c "shutdown" $(NULL)
else
%.flash: %.hex
@printf " FLASH $<\n"
@# IMPORTANT: Don't use "resume", only "reset" will work correctly!
$(Q)$(OOCD) -f interface/$(OOCD_INTERFACE).cfg \
-f board/$(OOCD_BOARD).cfg \
-c "ft2232_serial $(OOCD_SERIAL)" \
-c "init" -c "reset init" \
-c "flash write_image erase $(*).hex" \
-c "reset" \
-c "shutdown" $(NULL)
endif
else
%.flash: %.elf
@printf " GDB $(*).elf (flash)\n"
$(Q)$(GDB) --batch \
-ex 'target extended-remote $(BMP_PORT)' \
-x $(SCRIPT_DIR)/black_magic_probe_flash.scr \
$(*).elf
endif
else
%.flash: %.elf
@printf " GDB $(*).elf (flash)\n"
$(Q)$(GDB) --batch \
-ex 'target extended-remote $(STLINK_PORT)' \
-x $(SCRIPT_DIR)/stlink_flash.scr \
$(*).elf
endif
.PHONY: images clean stylecheck styleclean elf bin hex srec list
-include $(OBJS:.o=.d)

View File

@ -0,0 +1,44 @@
##
## This file is part of the libopencm3 project.
##
## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
## Copyright (C) 2010 Piotr Esden-Tempski <piotr@esden.net>
##
## This library is free software: you can redistribute it and/or modify
## it under the terms of the GNU Lesser General Public License as published by
## the Free Software Foundation, either version 3 of the License, or
## (at your option) any later version.
##
## This library is distributed in the hope that it will be useful,
## but WITHOUT ANY WARRANTY; without even the implied warranty of
## MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
## GNU Lesser General Public License for more details.
##
## You should have received a copy of the GNU Lesser General Public License
## along with this library. If not, see <http://www.gnu.org/licenses/>.
##
LIBNAME = opencm3_stm32f1
DEFS = -DSTM32F1
FP_FLAGS ?= -msoft-float
ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd
################################################################################
# OpenOCD specific variables
OOCD ?= openocd
OOCD_INTERFACE ?= flossjtag
OOCD_BOARD ?= olimex_stm32_h103
################################################################################
# Black Magic Probe specific variables
# Set the BMP_PORT to a serial port and then BMP is used for flashing
BMP_PORT ?=
################################################################################
# texane/stlink specific variables
#STLINK_PORT ?= :4242
include libopencm3.rules.mk

View File

@ -0,0 +1,141 @@
#include <libopencm3/stm32/rcc.h>
#include <libopencm3/stm32/gpio.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/cm3/systick.h>
#include <stdio.h>
#include <errno.h>
#include <unistd.h>
// Configuration
// LED2 on PA5
// Debug: USART2, TX on PA2
// Bluetooth: USART3. TX PB10, RX PB11, CTS PB13 (in), RTS PB14 (out), N_SHUTDOWN PB15
#define GPIO_LED2 GPIO5
#define USART_CONSOLE USART2
#define GPIO_BT_N_SHUTDOWN GPIO15
// btstack code starts there
void btstack_main(void);
// hal_tick.h inmplementation
#include <btstack/hal_tick.h>
static void dummy_handler(void);
static void (*tick_handler)(void) = &dummy_handler;
static void dummy_handler(void){};
void hal_tick_init(void){
/* clock rate / 1000 to get 1mS interrupt rate */
systick_set_reload(8000);
systick_set_clocksource(STK_CSR_CLKSOURCE_AHB);
systick_counter_enable();
systick_interrupt_enable();
}
void hal_tick_set_handler(void (*handler)(void)){
if (handler == NULL){
tick_handler = &dummy_handler;
return;
}
tick_handler = handler;
}
int hal_tick_get_tick_period_in_ms(void){
return 1;
}
void sys_tick_handler(void)
{
(*tick_handler)();
}
// hal_cpu.h implementation
#include <btstack/hal_cpu.h>
void hal_cpu_disable_irqs(void){
}
void hal_cpu_enable_irqs(void){
}
void hal_cpu_enable_irqs_and_sleep(void){
}
//
/**
* Use USART_CONSOLE as a console.
* This is a syscall for newlib
* @param file
* @param ptr
* @param len
* @return
*/
int _write(int file, char *ptr, int len);
int _write(int file, char *ptr, int len)
{
int i;
if (file == STDOUT_FILENO || file == STDERR_FILENO) {
for (i = 0; i < len; i++) {
if (ptr[i] == '\n') {
usart_send_blocking(USART_CONSOLE, '\r');
}
usart_send_blocking(USART_CONSOLE, ptr[i]);
}
return i;
}
errno = EIO;
return -1;
}
static void clock_setup(void)
{
/* Enable clocks for GPIO port A (for GPIO_USART1_TX) and USART1 + USART2. */
/* needs to be done before initializing other peripherals */
rcc_periph_clock_enable(RCC_GPIOA);
rcc_periph_clock_enable(RCC_GPIOB);
rcc_periph_clock_enable(RCC_USART2);
rcc_periph_clock_enable(RCC_USART3);
}
static void gpio_setup(void)
{
/* Set GPIO5 (in GPIO port A) to 'output push-pull'. [LED] */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, GPIO_LED2);
}
void usart_setup(void);
void usart_setup(void)
{
/* Setup GPIO pin GPIO_USART2_TX/GPIO2 on GPIO port A for transmit. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_USART2_TX);
/* Setup UART parameters. */
usart_set_baudrate(USART2, 9600);
usart_set_databits(USART2, 8);
usart_set_stopbits(USART2, USART_STOPBITS_1);
usart_set_mode(USART2, USART_MODE_TX);
usart_set_parity(USART2, USART_PARITY_NONE);
usart_set_flow_control(USART2, USART_FLOWCONTROL_NONE);
/* Finally enable the USART. */
usart_enable(USART2);
}
int main(void)
{
clock_setup();
gpio_setup();
usart_setup();
hal_tick_init();
// hand over to btstack embedded code
btstack_main();
return 0;
}

View File

@ -0,0 +1,7 @@
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
}
INCLUDE libopencm3_stm32f1.ld