add simple blink for ST32F103-nolib (Makefile still under construction!)

This commit is contained in:
eddyem 2018-11-05 11:42:01 +03:00
parent 34f6afb702
commit 4defefb860
16 changed files with 1024 additions and 715 deletions

View File

@ -0,0 +1 @@
__attribute__((fallthrough));

View File

@ -23,41 +23,73 @@
* used by the startup code generator (vector.c) to set the initial values for
* the interrupt handling routines to the chip family specific _isr weak
* symbols. */
#define NVIC_WWDG_IRQ 0
#define NVIC_PVD_IRQ 1
#define NVIC_RTC_IRQ 2
#define NVIC_FLASH_IRQ 3
#define NVIC_RCC_IRQ 4
#define NVIC_EXTI0_1_IRQ 5
#define NVIC_EXTI2_3_IRQ 6
#define NVIC_EXTI4_15_IRQ 7
#define NVIC_TSC_IRQ 8
#define NVIC_DMA1_CHANNEL1_IRQ 9
#define NVIC_DMA1_CHANNEL2_3_IRQ 10
#define NVIC_DMA1_CHANNEL4_5_IRQ 11
#define NVIC_ADC_COMP_IRQ 12
#define NVIC_TIM1_BRK_UP_TRG_COM_IRQ 13
#define NVIC_TIM1_CC_IRQ 14
#define NVIC_TIM2_IRQ 15
#define NVIC_TIM3_IRQ 16
#define NVIC_TIM6_DAC_IRQ 17
#define NVIC_TIM7_IRQ 18
#define NVIC_TIM14_IRQ 19
#define NVIC_TIM15_IRQ 20
#define NVIC_TIM16_IRQ 21
#define NVIC_TIM17_IRQ 22
#define NVIC_I2C1_IRQ 23
#define NVIC_I2C2_IRQ 24
#define NVIC_SPI1_IRQ 25
#define NVIC_SPI2_IRQ 26
#define NVIC_USART1_IRQ 27
#define NVIC_USART2_IRQ 28
#define NVIC_USART3_4_IRQ 29
#define NVIC_CEC_CAN_IRQ 30
#define NVIC_USB_IRQ 31
#define NVIC_IRQ_COUNT 32
#define F0_IRQ_HANDLERS \
wwdg_isr, \
pvd_isr, \
rtc_isr, \
flash_isr, \
rcc_isr, \
exti0_1_isr, \
exti2_3_isr, \
exti4_15_isr, \
tsc_isr, \
dma1_channel1_isr, \
dma1_channel2_3_isr, \
dma1_channel4_5_isr, \
adc_comp_isr, \
tim1_brk_up_trg_com_isr, \
tim1_cc_isr, \
tim2_isr, \
tim3_isr, \
tim6_dac_isr, \
tim7_isr, \
tim14_isr, \
tim15_isr, \
tim16_isr, \
tim17_isr, \
i2c1_isr, \
i2c2_isr, \
spi1_isr, \
spi2_isr, \
usart1_isr, \
usart2_isr, \
usart3_4_isr, \
cec_can_isr, \
usb_isr
[NVIC_WWDG_IRQ] = wwdg_isr, \
[NVIC_PVD_IRQ] = pvd_isr, \
[NVIC_RTC_IRQ] = rtc_isr, \
[NVIC_FLASH_IRQ] = flash_isr, \
[NVIC_RCC_IRQ] = rcc_isr, \
[NVIC_EXTI0_1_IRQ] = exti0_1_isr, \
[NVIC_EXTI2_3_IRQ] = exti2_3_isr, \
[NVIC_EXTI4_15_IRQ] = exti4_15_isr, \
[NVIC_TSC_IRQ] = tsc_isr, \
[NVIC_DMA1_CHANNEL1_IRQ] = dma1_channel1_isr, \
[NVIC_DMA1_CHANNEL2_3_IRQ] = dma1_channel2_3_isr, \
[NVIC_DMA1_CHANNEL4_5_IRQ] = dma1_channel4_5_isr, \
[NVIC_ADC_COMP_IRQ] = adc_comp_isr, \
[NVIC_TIM1_BRK_UP_TRG_COM_IRQ] = tim1_brk_up_trg_com_isr, \
[NVIC_TIM1_CC_IRQ] = tim1_cc_isr, \
[NVIC_TIM2_IRQ] = tim2_isr, \
[NVIC_TIM3_IRQ] = tim3_isr, \
[NVIC_TIM6_DAC_IRQ] = tim6_dac_isr, \
[NVIC_TIM7_IRQ] = tim7_isr, \
[NVIC_TIM14_IRQ] = tim14_isr, \
[NVIC_TIM15_IRQ] = tim15_isr, \
[NVIC_TIM16_IRQ] = tim16_isr, \
[NVIC_TIM17_IRQ] = tim17_isr, \
[NVIC_I2C1_IRQ] = i2c1_isr, \
[NVIC_I2C2_IRQ] = i2c2_isr, \
[NVIC_SPI1_IRQ] = spi1_isr, \
[NVIC_SPI2_IRQ] = spi2_isr, \
[NVIC_USART1_IRQ] = usart1_isr, \
[NVIC_USART2_IRQ] = usart2_isr, \
[NVIC_USART3_4_IRQ] = usart3_4_isr, \
[NVIC_CEC_CAN_IRQ] = cec_can_isr, \
[NVIC_USB_IRQ] = usb_isr
typedef void (*vector_table_entry_t)(void);
typedef void (*funcp_t) (void);

Binary file not shown.

View File

@ -0,0 +1,9 @@
LEDs: PB8 - D2, PB9 - D1 (connected to +3.3V)
Buttons: PC0 - S2, PC1 - S3 (no pullup/down resistors! Connected to ground)
UNUSED due to JTAG: PA13, PA14, PA15, PB3, PB4.
RS232 (due to jumpers @ P4): PA9, PA10, PA2, PA3
J6 - USB pullup on/off

View File

@ -115,9 +115,8 @@ TRUE_INLINE void StartHSE()
/* Enable PLL2 */
RCC->CR |= RCC_CR_PLL2ON;
/* Wait till PLL2 is ready */
while((RCC->CR & RCC_CR_PLL2RDY) == 0)
{
}
StartUpCounter = 0;
while((RCC->CR & RCC_CR_PLL2RDY) == 0 && ++StartUpCounter < 1000){}
/* PLL configuration: PLLCLK = PREDIV1 * 9 = 72 MHz */
RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL);
@ -134,18 +133,16 @@ TRUE_INLINE void StartHSE()
RCC->CR |= RCC_CR_PLLON;
/* Wait till PLL is ready */
while((RCC->CR & RCC_CR_PLLRDY) == 0)
{
}
StartUpCounter = 0;
while((RCC->CR & RCC_CR_PLLRDY) == 0 && ++StartUpCounter < 1000){}
/* Select PLL as system clock source */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
/* Wait till PLL is used as system clock source */
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08)
{
}
StartUpCounter = 0;
while(((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08) && ++StartUpCounter < 1000){}
}
else // HSE fails to start-up
{

View File

@ -451,7 +451,7 @@ typedef enum IRQn
*/
#include "core_cm3.h"
//#include "system_stm32f10x.h"
#include <stdint.h>
/** @addtogroup Exported_types

View File

@ -22,14 +22,6 @@
#ifndef VECTOR_H
#define VECTOR_H
typedef void (*vector_table_entry_t)(void);
typedef void (*funcp_t) (void);
/* Symbols exported by the linker script(s): */
extern unsigned _data_loadaddr, _data, _edata, _ebss, _stack;
extern funcp_t __preinit_array_start, __preinit_array_end;
extern funcp_t __init_array_start, __init_array_end;
extern funcp_t __fini_array_start, __fini_array_end;
#ifndef WEAK
#define WEAK __attribute__((weak))
#endif

View File

@ -1 +0,0 @@
including files

View File

@ -1,106 +1,87 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
*
* 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/>.
*/
********************************************************************************
* *
* Copyright (c) 2017 Andrea Loi *
* *
* Permission is hereby granted, free of charge, to any person obtaining a *
* copy of this software and associated documentation files (the "Software"), *
* to deal in the Software without restriction, including without limitation *
* the rights to use, copy, modify, merge, publish, distribute, sublicense, *
* and/or sell copies of the Software, and to permit persons to whom the *
* Software is furnished to do so, subject to the following conditions: *
* *
* The above copyright notice and this permission notice shall be included *
* in all copies or substantial portions of the Software. *
* *
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR *
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, *
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL *
* THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER *
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING *
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER *
* DEALINGS IN THE SOFTWARE. *
* *
********************************************************************************
*/
/* Generic linker script for STM32 targets using libopencm3. */
/* Memory regions must be defined in the ld script which includes this one. */
/* Enforce emmition of the vector table. */
EXTERN (vector_table)
/******************************************************************************/
/* DON'T EDIT THIS FILE UNLESS YOU KNOW WHAT YOU'RE DOING! */
/******************************************************************************/
/* _isrvectors_tend = 0x00000150; - different for different series */
/* Define the entry point of the output file. */
ENTRY(reset_handler)
/* Define sections. */
SECTIONS
{
.text : {
*(.vectors) /* Vector table */
*(.text*) /* Program code */
. = ALIGN(4);
*(.rodata*) /* Read-only data */
. = ALIGN(4);
} >rom
SECTIONS {
.vector_table 0x08000000 :
{
_sisrvectors = .;
KEEP(*(.vector_table))
/* ASSERT(. == _isrvectors_tend, "The vector table needs to be 84 elements long!"); */
_eisrvectors = .;
} >rom
/* C++ Static constructors/destructors, also used for __attribute__
* ((constructor)) and the likes */
.preinit_array : {
. = ALIGN(4);
__preinit_array_start = .;
KEEP (*(.preinit_array))
__preinit_array_end = .;
} >rom
.init_array : {
. = ALIGN(4);
__init_array_start = .;
KEEP (*(SORT(.init_array.*)))
KEEP (*(.init_array))
__init_array_end = .;
} >rom
.fini_array : {
. = ALIGN(4);
__fini_array_start = .;
KEEP (*(.fini_array))
KEEP (*(SORT(.fini_array.*)))
__fini_array_end = .;
} >rom
.text :
{
. = ALIGN(4);
_stext = .;
*(.text*)
*(.rodata*)
. = ALIGN(4);
_etext = .;
} >rom
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} >rom
.ARM : {
*(.ARM.exidx*)
} >rom
.data :
{
. = ALIGN(4);
_sdata = .;
*(.data*)
. = ALIGN(4);
_edata = .;
} >ram AT >rom
/*
* Another section used by C++ stuff, appears when using newlib with
* 64bit (long long) printf support
*/
.ARM.extab : {
*(.ARM.extab*)
} >rom
.ARM.exidx : {
__exidx_start = .;
*(.ARM.exidx*)
__exidx_end = .;
} >rom
_ldata = LOADADDR(.data);
. = ALIGN(4);
_etext = .;
.data : {
_data = .;
*(.data*) /* Read-write initialized data */
. = ALIGN(4);
_edata = .;
} >ram AT >rom
_data_loadaddr = LOADADDR(.data);
.bss : {
*(.bss*) /* Read-write zero initialized data */
*(COMMON)
. = ALIGN(4);
_ebss = .;
} >ram
/*
* The .eh_frame section appears to be used for C++ exception handling.
* You may need to fix this if you're using C++.
*/
/DISCARD/ : { *(.eh_frame) }
. = ALIGN(4);
end = .;
.bss :
{
. = ALIGN(4);
_sbss = .;
*(.bss*)
*(COMMON)
. = ALIGN(4);
_ebss = .;
} >ram
}
PROVIDE(_stack = ORIGIN(ram) + LENGTH(ram));
PROVIDE(_stack = ORIGIN(ram) + LENGTH(ram));

File diff suppressed because it is too large Load Diff

View File

@ -11,11 +11,13 @@ DEFS = -DEBUG
# change this linking script depending on particular MCU model,
# for example, if you have STM32F103VBT6, you should write:
LDSCRIPT ?= ld/stm32f103xB.ld
#LDSCRIPT = STM32F103C8.ld
INDEPENDENT_HEADERS=
FP_FLAGS ?= -msoft-float
ASM_FLAGS ?= -mthumb -mcpu=cortex-m3 -mfix-cortex-m3-ldrd
ASM_FLAGS ?= -mthumb -mcpu=cortex-m3
#-mfix-cortex-m3-ldrd
ARCH_FLAGS = $(ASM_FLAGS) $(FP_FLAGS)
###############################################################################
@ -25,9 +27,10 @@ PREFIX ?= arm-none-eabi
RM := rm -f
RMDIR := rmdir
CC := $(PREFIX)-gcc
LD := $(PREFIX)-gcc
LD := $(PREFIX)-ld
AR := $(PREFIX)-ar
AS := $(PREFIX)-as
SIZE := $(PREFIX)-size
OBJCOPY := $(PREFIX)-objcopy
OBJDUMP := $(PREFIX)-objdump
GDB := $(PREFIX)-gdb
@ -51,25 +54,28 @@ LIB_DIR := $(INC_DIR)/ld
###############################################################################
# C flags
CFLAGS += -O2 -g -MD -D__thumb2__=1
CFLAGS += -Wall -Werror -Wextra -Wshadow -Wimplicit-function-declaration
CFLAGS += -Wredundant-decls
CFLAGS += -O0 -g
# -MD -D__thumb2__=1
#CFLAGS += -Wall -Werror -Wextra -Wshadow -Wimplicit-function-declaration
#CFLAGS += -Wredundant-decls
# -Wmissing-prototypes -Wstrict-prototypes
CFLAGS += -fno-common -ffunction-sections -fdata-sections
CFLAGS += -fno-common
#-ffunction-sections -fdata-sections
###############################################################################
# Linker flags
LDFLAGS += --static -nostartfiles
LDFLAGS += -nostartfiles
# --static
#--specs=nano.specs
LDFLAGS += -L$(LIB_DIR)
LDFLAGS += -T$(LDSCRIPT)
LDFLAGS += -Wl,-Map=$(OBJDIR)/$(BINARY).map
LDFLAGS += -Wl,--gc-sections
#LDFLAGS += -Wl,-Map=$(OBJDIR)/$(BINARY).map
#LDFLAGS += -Wl,--gc-sections
###############################################################################
# Used libraries
LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group
LDLIBS += $(shell $(CC) $(CFLAGS) -print-libgcc-file-name)
#LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group
#LDLIBS += $(shell $(CC) $(CFLAGS) -print-libgcc-file-name)
DEFS += -DSTM32$(FAMILY) -DSTM32$(MCU) -DSTM32F10X_$(DENSITY)
@ -82,7 +88,7 @@ LIST := $(OBJDIR)/$(BINARY).list
BIN := $(BINARY).bin
HEX := $(BINARY).hex
all: bin list
all: bin list size
elf: $(ELF)
bin: $(BIN)
@ -120,7 +126,10 @@ $(LIST): $(ELF)
$(ELF): $(OBJDIR) $(OBJS)
@echo " LD $(ELF)"
$(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF)
$(LD) $(LDFLAGS) $(OBJS) $(LDLIBS) -o $(ELF)
size: $(ELF)
$(SIZE) $(ELF)
clean:
@echo " CLEAN"

View File

@ -1,3 +1,5 @@
Toggle LEDs (PB8/PB9) on STM32F103 development board depending on buttons PC0,PC1:
- no jumper == 'SOS' in Morze
- with jumper - blink with period of 4 seconds
- no buttons pressed == 'SOS' in Morze @ LED D1
- Button S2 pressed - D1 blinks with period of 5s
- Button S1 pressed - D2 blinks with period of 1s

Binary file not shown.

View File

@ -1,7 +1,7 @@
/*
* systick_blink.c
* main.c
*
* Copyright 2017 Edward V. Emelianoff <eddy@sao.ru, edward.emelianoff@gmail.com>
* Copyright 2018 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
@ -21,30 +21,24 @@
#include "stm32f1.h"
static volatile uint8_t blink_ctr = 0;
static volatile uint32_t blink_ctr = 0;
/* Called when systick fires */
void sys_tick_handler(void){
++blink_ctr;
}
/*
* Set up timer to fire every x milliseconds
*/
// SysTick is 24 bit counter, so 16777215 - max value!!!
// After HSE is ON it works @9MHz (????)
static void systick_setup(uint32_t xms){
static uint32_t curms = 0;
if(curms == xms) return;
// 6MHz - HCLK/8 (due to HPRE=1 HCLK=SYSCLK)
// this function also clears counter so it starts right away
SysTick_Config(6000 * xms);
SysTick_Config(72000 * xms);
curms = xms;
}
/* set STM32 to clock by 48MHz from HSI oscillator */
//static void clock_setup(void){
//StartHSE(RCC_CR_CSSON | RCC_CR_HSEBYP);
//}
static const uint16_t L[] = {125,100,125,100,125,200, 60,100,60,100,60,200, 125,100,125,100,125, 230};
static void gpio_setup(void){
/* Enable clocks to the GPIO subsystems (A&B) */
@ -56,42 +50,13 @@ static void gpio_setup(void){
GPIOC->CRL = CRL(0, CNF_PUDINPUT|MODE_INPUT) | CRL(1, CNF_PUDINPUT|MODE_INPUT);
}
static const uint16_t L[] = {125,100,125,100,125,200, 350,100,350,100,350,200, 125,100,125,100,125, 1000};
int main(void){
int main(){
sysreset();
// AFIO->MAPR = AFIO_MAPR_SWJ_CFG_DISABLE; // turn off jtag and swim
// StartHSE();
RCC->CFGR &= ~RCC_CFGR_SW; // Change System Clock to HSI
while ((RCC->CFGR & RCC_CFGR_SWS) != 0x00) {
__NOP();
};
RCC->CR &= ~RCC_CR_PLLON; // Disable Pll
while ((RCC->CR & RCC_CR_PLLON)) {
__NOP();
};
RCC->CFGR &= ~0x3C0000;
RCC->CFGR |= RCC_CFGR_PLLMULL4; // Set Pll Mul to 4
RCC->CFGR |= RCC_CFGR_USBPRE;
RCC->CFGR |= RCC_CFGR_PLLSRC;
RCC->CR |= RCC_CR_PLLON;
while (!(RCC->CR & RCC_CR_PLLON)) {
__NOP();
};
RCC->CFGR |= RCC_CFGR_SW_1; // Change System Clock to PLL
while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_1) {
__NOP();
};
StartHSE();
gpio_setup();
/* 500ms ticks => 1000ms period => 1Hz blinks */
systick_setup(100);
uint8_t oldctr = blink_ctr+1;
pin_clear(GPIOB, 1<<8);
pin_clear(GPIOB, 1<<9);
for(int i = 0; i < 1000000; ++i) nop();
uint32_t oldctr = 0xff;
pin_clear(GPIOB, 3<<8);
/* Do nothing in main loop */
while (1){
if(pin_read(GPIOC, 1) && pin_read(GPIOC, 2)){ // no buttons present - morze @ LED1 (PB9)
@ -103,13 +68,22 @@ RCC->CFGR &= ~RCC_CFGR_SW; // Change System Clock to HSI
oldctr = blink_ctr;
}
}else{ // button pressed: turn ON given LED
if(pin_read(GPIOC, 1)){ // PC0 pressed (button S2)
pin_clear(GPIOB, 1<<8);
}else pin_set(GPIOB, 1<<8);
if(pin_read(GPIOC, 2)){ // PC1 pressed (button S3)
pin_clear(GPIOB, 1<<9);
if(pin_read(GPIOC, 1) == 0){ // PC0 pressed (button S2)
systick_setup(5);
if(blink_ctr - oldctr > 499){
pin_toggle(GPIOB, 1<<9);
oldctr = blink_ctr;
}
}else pin_set(GPIOB, 1<<9);
if(pin_read(GPIOC, 2) == 0){ // PC1 pressed (button S3)
systick_setup(1);
if(blink_ctr - oldctr > 499){
pin_toggle(GPIOB, 1<<8);
oldctr = blink_ctr;
}
}else pin_set(GPIOB, 1<<8);
}
}
}

View File

@ -1,31 +0,0 @@
/*
* systick_blink.c
*
* Copyright 2017 Edward V. Emelianoff <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*/
#include "stm32f1.h"
int main(void){
sysreset();
RCC->APB2ENR |= RCC_APB2ENR_IOPBEN;
GPIOB->CRH = 0x00000066; // PB8/9 - 2MHz opendrain
GPIOB->ODR = 0;
while(1){}
return 0;
}

View File

@ -1,30 +0,0 @@
/*
* systick_blink.c
*
* Copyright 2017 Edward V. Emelianoff <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*/
#include "stm32f1.h"
int main(void){
RCC->APB2ENR |= RCC_APB2ENR_IOPBEN;
GPIOB->CRH = 0x00000066; // PB8/9 - 2MHz opendrain
GPIOB->ODR = 0;
while(1){}
return 0;
}