This commit is contained in:
olikraus 2017-12-19 19:38:40 +01:00
parent 745098e510
commit 3bcdae1dcd
7 changed files with 1273 additions and 0 deletions

View File

@ -0,0 +1,148 @@
#
# Generic and Simple GNU ARM Makefile
#
# Desinged for the gnu-arm-none-eabi tool chain
#
# Features
# - create hex file
# - create assembler listing (.dis)
#
# Limitations
# - only C-files supported
# - no automatic dependency checking (call 'make clean' if any .h files are changed)
#
# Targets:
# make
# create hex file, no upload
# make upload
# create and upload hex file
# make clean
# delete all generated files
#
# Note:
# Display list make database: make -p -f/dev/null | less
#
#================================================
# External tools
# The base directory of gcc-arm-none-eabi
# Can be empty on Ubuntu and installed gcc-arm-none-eabi
# If set, GCCBINPATH must contain a "/" at the end.
GCCBINPATH:=/usr/bin/
#================================================
# Project Information
# The name for the project
TARGETNAME:=si9986_scope
# The source files of the project
CSRC:=$(wildcard *.c)
SSRC:=$(wildcard ../stm32l0xx/src/*.s)
# The CPU architecture (will be used for -mcpu)
# for the LPC824, can we use "cortex-m0plus"?
MCPU:=cortex-m0plus
# Include directory for the system include files
SYSINC:=../stm32l0xx/inc
SYSSRC:=$(wildcard ../stm32l0xx/src/*.c)
# Include directory for the u8g2 include files
U8G2INC:=../../../../csrc/
U8G2SRC:=$(wildcard ../../../../csrc/*.c)
# directory for FatFS
#FFINC:=../fatfs
#FFSRC:=$(wildcard ../fatfs/*.c)
# Directory for the linker script
LDSCRIPTDIR:=.
# Name of the linker script (must be the "keep" script, because the other script is not always working)
LDSCRIPT:=stm32l031x6.ld
#================================================
# Main part of the Makefile starts here. Usually no changes are needed.
# Internal Variable Names
LIBNAME:=$(TARGETNAME).a
ELFNAME:=$(TARGETNAME).elf
HEXNAME:=$(TARGETNAME).hex
DISNAME:=$(TARGETNAME).dis
MAPNAME:=$(TARGETNAME).map
OBJ:=$(CSRC:.c=.o) $(SSRC:.s=.o) $(SYSSRC:.c=.o) $(U8G2SRC:.c=.o)
# $(SYSSRC:.c=.o) $(FFSRC:.c=.o)
# Replace standard build tools by arm tools
AS:=$(GCCBINPATH)arm-none-eabi-as
CC:=$(GCCBINPATH)arm-none-eabi-gcc
AR:=$(GCCBINPATH)arm-none-eabi-ar
OBJCOPY:=$(GCCBINPATH)arm-none-eabi-objcopy
OBJDUMP:=$(GCCBINPATH)arm-none-eabi-objdump
SIZE:=$(GCCBINPATH)arm-none-eabi-size
# Common flags
COMMON_FLAGS = -mthumb -mcpu=$(MCPU)
COMMON_FLAGS += -DSTM32L031xx
COMMON_FLAGS += -Wall -I. -I$(SYSINC) -I$(U8G2INC)
# define stack size (defaults to 0x0100)
# COMMON_FLAGS += -D__STACK_SIZE=0x0100
# COMMON_FLAGS += -Os -flto
COMMON_FLAGS += -Os
# COMMON_FLAGS += -fstack-protector
# COMMON_FLAGS += -finstrument-functions
# Do not use stand libs startup code. Uncomment this for gcclib procedures
# memcpy still works, but might be required for __aeabi_uidiv
# COMMON_FLAGS += -nostdlib
# remove unused data and function
#COMMON_FLAGS += -ffunction-sections -fdata-sections -fshort-wchar
COMMON_FLAGS += -ffunction-sections -fdata-sections
# C flags
CFLAGS:=$(COMMON_FLAGS) -std=gnu99
# LD flags
# remove unreferenced procedures and variables, but __isr_vector
GC:=-Wl,--gc-sections -Wl,--undefined=__isr_vector
MAP:=-Wl,-Map=$(MAPNAME)
LFLAGS:=$(COMMON_FLAGS) $(GC) $(MAP)
#LDLIBS:=--specs=nosys.specs -lc -lc -lnosys -L$(LDSCRIPTDIR) -T $(LDSCRIPT)
LDLIBS:=--specs=nosys.specs -L$(LDSCRIPTDIR) -T $(LDSCRIPT)
# Additional Suffixes
.SUFFIXES: .elf .hex .bin .dis
# Targets
.PHONY: all
all: $(DISNAME) $(HEXNAME)
$(SIZE) $(ELFNAME)
.PHONY: upload
upload: $(DISNAME) $(HEXNAME) $(ELFNAME)
stm32flash -e 255 -g 0 -w $(HEXNAME) -v /dev/ttyUSB0
$(SIZE) $(ELFNAME)
.PHONY: clean
clean:
$(RM) $(OBJ) $(HEXNAME) $(ELFNAME) $(LIBNAME) $(DISNAME) $(MAPNAME) libssp.a libssp_nonshared.a
# implicit rules
.elf.hex:
$(OBJCOPY) -O ihex $< $@
# explicit rules
$(ELFNAME): $(LIBNAME)($(OBJ)) libssp.a libssp_nonshared.a
$(LINK.o) $(LFLAGS) $(LIBNAME) $(LDLIBS) -o $@
$(DISNAME): $(ELFNAME)
$(OBJDUMP) -D -S $< > $@
# create empty ssp libs for -fstack-protector-all -fstack-protector
libssp.a:
$(AR) rcs $@
libssp_nonshared.a:
$(AR) rcs $@

View File

@ -0,0 +1,129 @@
/*
delay.c
The delay function delay_micro_seconds() will use the global variable
SystemCoreClock. A call to SystemCoreClockUpdate() is required before
using delay_micro_seconds().
STM32L031 Project (U8g2 Library)
Copyright (c) 2017, olikraus@gmail.com
All rights reserved.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list
of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice, this
list of conditions and the following disclaimer in the documentation and/or other
materials provided with the distribution.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "stm32l031xx.h"
/* Generic ARM delay procedure, based on the system timer (SysTick) */
/*
Delay by the provided number of system ticks.
The delay must be smaller than the RELOAD value.
This delay has an imprecision of about +/- 20 system ticks.
*/
static void _delay_system_ticks_sub(uint32_t sys_ticks)
{
uint32_t start_val, end_val, curr_val;
uint32_t load;
start_val = SysTick->VAL;
start_val &= 0x0ffffffUL;
end_val = start_val;
if ( end_val < sys_ticks )
{
/* check, if the operation after this if clause would lead to a negative result */
/* if this would be the case, then add the reload value first */
load = SysTick->LOAD;
load &= 0x0ffffffUL;
end_val += load;
}
/* counter goes towards zero, so end_val is below start value */
end_val -= sys_ticks;
/* wait until interval is left */
if ( start_val >= end_val )
{
for(;;)
{
curr_val = SysTick->VAL;
curr_val &= 0x0ffffffUL;
if ( curr_val <= end_val )
break;
if ( curr_val > start_val )
break;
}
}
else
{
for(;;)
{
curr_val = SysTick->VAL;
curr_val &= 0x0ffffffUL;
if ( curr_val <= end_val && curr_val > start_val )
break;
}
}
}
/*
Delay by the provided number of system ticks.
Any values between 0 and 0x0ffffffff are allowed.
*/
void delay_system_ticks(uint32_t sys_ticks)
{
uint32_t load4;
load4 = SysTick->LOAD;
load4 &= 0x0ffffffUL;
load4 >>= 2;
while ( sys_ticks > load4 )
{
sys_ticks -= load4;
_delay_system_ticks_sub(load4);
}
_delay_system_ticks_sub(sys_ticks);
}
/*
Delay by the provided number of micro seconds.
Limitation: "us" * System-Freq in MHz must not overflow in 32 bit.
Values between 0 and 1.000.000 (1 second) are ok.
Important: Call SystemCoreClockUpdate() before calling this function.
*/
void delay_micro_seconds(uint32_t us)
{
uint32_t sys_ticks;
sys_ticks = SystemCoreClock;
sys_ticks /=1000000UL;
sys_ticks *= us;
delay_system_ticks(sys_ticks);
}

View File

@ -0,0 +1,55 @@
/*
delay.h
LPC11U3x GPS Logger (https://github.com/olikraus/lpc11u3x-gps-logger)
Copyright (c) 2016, olikraus@gmail.com
All rights reserved.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list
of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice, this
list of conditions and the following disclaimer in the documentation and/or other
materials provided with the distribution.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef _DELAY_H
#define _DELAY_H
#include <stdint.h>
/*
Delay by the provided number of system ticks.
Any values between 0 and 0x0ffffffff are allowed.
*/
void delay_system_ticks(uint32_t sys_ticks);
/*
Delay by the provided number of micro seconds.
Limitation: "us" * System-Freq in MHz must now overflow in 32 bit.
Values between 0 and 1.000.000 (1 second) are ok.
Important: Call SystemCoreClockUpdate() before calling this function.
*/
void delay_micro_seconds(uint32_t us);
#endif /* _DELAY_H */

View File

@ -0,0 +1,583 @@
/*
si9986 scope for DC motor
Example for the STM32L031 Eval Board with 128x64 OLED at PA13/PA14
SI9986 Shield
SI9986 IN_A: PA1 / AF2: TIM2_CH2
SI9986 IN_B: PB1 / AF?: TIM2_CH4
VarRes: PA5 / ADC CH5
Voltage sense: PA6 / ADC CH6
IN_A IN_B OUT_A OUT_B
1 0 1 0
0 1 0 1
0 0 0 0
1 1 HiZ HiZ
*/
#include <stdio.h>
#include "stm32l031xx.h"
#include "delay.h"
#include "u8g2.h"
/*=======================================================================*/
/* external functions */
uint8_t u8x8_gpio_and_delay_stm32l0(u8x8_t *u8x8, uint8_t msg, uint8_t arg_int, void *arg_ptr);
/*=======================================================================*/
/* global variables */
u8g2_t u8g2; // u8g2 object
uint8_t u8g2_x, u8g2_y; // current position on the screen
volatile unsigned long SysTickCount = 0;
/*=======================================================================*/
void __attribute__ ((interrupt, used)) SysTick_Handler(void)
{
SysTickCount++;
}
void setHSIClock()
{
/* test if the current clock source is something else than HSI */
if ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_HSI)
{
/* enable HSI */
RCC->CR |= RCC_CR_HSION;
/* wait until HSI becomes ready */
while ( (RCC->CR & RCC_CR_HSIRDY) == 0 )
;
/* enable the HSI "divide by 4" bit */
RCC->CR |= (uint32_t)(RCC_CR_HSIDIVEN);
/* wait until the "divide by 4" flag is enabled */
while((RCC->CR & RCC_CR_HSIDIVF) == 0)
;
/* then use the HSI clock */
RCC->CFGR = (RCC->CFGR & (uint32_t) (~RCC_CFGR_SW)) | RCC_CFGR_SW_HSI;
/* wait until HSI clock is used */
while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_HSI)
;
}
/* disable PLL */
RCC->CR &= (uint32_t)(~RCC_CR_PLLON);
/* wait until PLL is inactive */
while((RCC->CR & RCC_CR_PLLRDY) != 0)
;
/* set latency to 1 wait state */
FLASH->ACR |= FLASH_ACR_LATENCY;
/* At this point the HSI runs with 4 MHz */
/* Multiply by 16 device by 2 --> 32 MHz */
RCC->CFGR = (RCC->CFGR & (~(RCC_CFGR_PLLMUL| RCC_CFGR_PLLDIV ))) | (RCC_CFGR_PLLMUL16 | RCC_CFGR_PLLDIV2);
/* enable PLL */
RCC->CR |= RCC_CR_PLLON;
/* wait until the PLL is ready */
while ((RCC->CR & RCC_CR_PLLRDY) == 0)
;
/* use the PLL has clock source */
RCC->CFGR |= (uint32_t) (RCC_CFGR_SW_PLL);
/* wait until the PLL source is active */
while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL)
;
SystemCoreClockUpdate(); /* Update SystemCoreClock global variable */
}
/*
Enable several power regions: PWR, GPIOA
This must be executed after each reset.
*/
void startUp(void)
{
RCC->IOPENR |= RCC_IOPENR_IOPAEN; /* Enable clock for GPIO Port A */
RCC->APB1ENR |= RCC_APB1ENR_PWREN; /* enable power interface (PWR) */
PWR->CR |= PWR_CR_DBP; /* activate write access to RCC->CSR and RTC */
SysTick->LOAD = (SystemCoreClock/1000)*50 - 1; /* 50ms task */
SysTick->VAL = 0;
SysTick->CTRL = 7; /* enable, generate interrupt (SysTick_Handler), do not divide by 2 */
}
/*=======================================================================*/
/* u8x8 display procedures */
void initDisplay(void)
{
/* setup display */
u8g2_Setup_ssd1306_i2c_128x64_noname_f(&u8g2, U8G2_R0, u8x8_byte_sw_i2c, u8x8_gpio_and_delay_stm32l0);
u8g2_InitDisplay(&u8g2);
u8g2_SetPowerSave(&u8g2, 0);
u8g2_SetFont(&u8g2, u8g2_font_6x12_tf);
u8g2_ClearBuffer(&u8g2);
u8g2_DrawStr(&u8g2, 0,12, "STM32L031");
u8g2_DrawStr(&u8g2, 0,24, u8x8_u8toa(SystemCoreClock/1000000, 2));
u8g2_DrawStr(&u8g2, 20,24, "MHz");
u8g2_SendBuffer(&u8g2);
u8g2_x = 0;
u8g2_y = 0;
}
void outChar(uint8_t c)
{
u8g2_x+=u8g2_DrawGlyph(&u8g2, u8g2_x, u8g2_y, c);
}
void outStr(const char *s)
{
while( *s )
outChar(*s++);
}
void outHexHalfByte(uint8_t b)
{
b &= 0x0f;
if ( b < 10 )
outChar(b+'0');
else
outChar(b+'a'-10);
}
void outHex8(uint8_t b)
{
outHexHalfByte(b >> 4);
outHexHalfByte(b);
}
void outHex16(uint16_t v)
{
outHex8(v>>8);
outHex8(v);
}
void outHex32(uint32_t v)
{
outHex16(v>>16);
outHex16(v);
}
void setRow(uint8_t r)
{
u8g2_x = 0;
u8g2_y = r;
}
/*=======================================================================*/
/* STOP ANY ADC CONVERSION */
void stopADC(void)
{
ADC1->CR |= ADC_CR_ADSTP;
while(ADC1->CR & ADC_CR_ADSTP)
;
}
/* CONFIGURATION with ADEN=0 */
/* required to change the configuration of the ADC */
void disableADC(void)
{
/* Check for the ADEN flag. */
/* Setting ADDIS will fail if the ADC is alread disabled: The while loop will not terminate */
if ((ADC1->CR & ADC_CR_ADEN) != 0)
{
/* is this correct? i think we must use the disable flag here */
ADC1->CR |= ADC_CR_ADDIS;
while(ADC1->CR & ADC_CR_ADDIS)
;
}
}
/* ENABLE ADC (but do not start) */
/* after the ADC is enabled, it must not be reconfigured */
void enableADC(void)
{
ADC1->ISR |= ADC_ISR_ADRDY; /* clear ready flag */
ADC1->CR |= ADC_CR_ADEN; /* enable ADC */
while ((ADC1->ISR & ADC_ISR_ADRDY) == 0) /* wait for ADC */
{
}
}
void initADC(void)
{
//__disable_irq();
/* ADC Clock Enable */
RCC->APB2ENR |= RCC_APB2ENR_ADCEN; /* enable ADC clock */
__NOP(); /* let us wait for some time */
__NOP(); /* let us wait for some time */
/* ADC Reset */
RCC->APB2RSTR |= RCC_APB2RSTR_ADCRST;
__NOP(); /* let us wait for some time */
__NOP(); /* let us wait for some time */
RCC->APB2RSTR &= ~RCC_APB2RSTR_ADCRST;
__NOP(); /* let us wait for some time */
__NOP(); /* let us wait for some time */
/* ADC Basic Setup */
ADC1->IER = 0; /* do not allow any interrupts */
ADC1->CFGR2 &= ~ADC_CFGR2_CKMODE; /* select HSI16 clock */
ADC1->CFGR1 = ADC_CFGR1_RES_1; /* 8 bit resolution */
ADC1->CR |= ADC_CR_ADVREGEN; /* enable ADC voltage regulator, probably not required, because this is automatically activated */
ADC->CCR |= ADC_CCR_VREFEN; /* Wake-up the VREFINT */
ADC->CCR |= ADC_CCR_TSEN; /* Wake-up the temperature sensor */
__NOP(); /* let us wait for some time */
__NOP(); /* let us wait for some time */
/* CALIBRATION */
if ((ADC1->CR & ADC_CR_ADEN) != 0) /* clear ADEN flag if required */
{
/* is this correct? i think we must use the disable flag here */
ADC1->CR &= (uint32_t)(~ADC_CR_ADEN);
}
ADC1->CR |= ADC_CR_ADCAL; /* start calibration */
while ((ADC1->ISR & ADC_ISR_EOCAL) == 0) /* wait for clibration finished */
{
}
ADC1->ISR |= ADC_ISR_EOCAL; /* clear the status flag, by writing 1 to it */
__NOP(); /* not sure why, but some nop's are required here, at least 4 of them */
__NOP();
__NOP();
__NOP();
__NOP();
__NOP();
/* CONFIGURATION with ADEN=0 */
disableADC();
//ADC1->CFGR1 &= ~ADC_CFGR1_RES; /* 12 bit resolution */
ADC1->CFGR1 = ADC_CFGR1_RES_1; /* 8 bit resolution */
enableADC();
}
/*
ch0 PA0 pin 6
ch1 PA1 pin 7
ch2 PA2 pin 8
ch3 PA3 pin 9
ch4 PA4 pin 10
ch5 PA5 pin 11
ch6 PA6 pin 12
ch7 PA7 pin 13
ch8 PB0 -
ch9 PB1 pin 14
ch 0..15: GPIO
ch 16: ???
ch 17: vref (bandgap)
ch18: temperature sensor
returns 12 bit result, right aligned
*/
uint16_t getADC(uint8_t ch)
{
//uint32_t i;
stopADC();
disableADC();
/* CONFIGURE ADC */
//ADC1->CFGR1 &= ~ADC_CFGR1_EXTEN; /* software enabled conversion start */
//ADC1->CFGR1 &= ~ADC_CFGR1_ALIGN; /* right alignment */
ADC1->CFGR1 = ADC_CFGR1_RES_1; /* 8 bit resolution */
//ADC1->SMPR |= ADC_SMPR_SMP_0 | ADC_SMPR_SMP_1 | ADC_SMPR_SMP_2; /* Select a sampling mode of 111 (very slow)*/
ADC1->SMPR = 0;
enableADC();
ADC1->CHSELR = 1<<ch; /* Select channel (can be done also if ADC is enabled) */
/* DO CONVERSION */
ADC1->CR |= ADC_CR_ADSTART; /* start the ADC conversion */
while ((ADC1->ISR & ADC_ISR_EOC) == 0) /* wait end of conversion */
{
}
return ADC1->DR;
}
void scanADC(uint8_t ch, uint16_t cnt, uint8_t *buf)
{
stopADC();
disableADC();
RCC->AHBENR |= RCC_AHBENR_DMAEN; /* enable DMA clock */
__NOP(); __NOP(); /* extra delay for clock stabilization required? */
/* disable and reset to defaults */
DMA1_Channel1->CCR = 0;
/* defaults:
- 8 Bit access --> ok
- read from peripheral --> ok
- none-circular mode --> ok
- no increment mode --> will be changed below
*/
DMA1_Channel1->CNDTR = cnt; /* buffer size */
DMA1_Channel1->CPAR = (uint32_t)&(ADC1->DR); /* source value */
DMA1_Channel1->CMAR = (uint32_t)buf; /* destination memory */
DMA1_CSELR->CSELR &= ~DMA_CSELR_C1S; /* 0000: select ADC for DMA CH 1 (this is reset default) */
DMA1_Channel1->CCR |= DMA_CCR_MINC; /* increment memory */
DMA1_Channel1->CCR |= DMA_CCR_EN; /* enable */
/*
detect rising edge on external trigger (ADC_CFGR1_EXTEN_0)
recive trigger from TIM2 (ADC_CFGR1_EXTSEL_1)
8 Bit resolution (ADC_CFGR1_RES_1)
Use DMA one shot mode and enable DMA (ADC_CFGR1_DMAEN)
Once DMA is finished, it will disable continues mode (ADC_CFGR1_CONT)
*/
ADC1->CFGR1 = ADC_CFGR1_EXTEN_0 /* rising edge */
| ADC_CFGR1_EXTSEL_1 /* TIM2 */
| ADC_CFGR1_RES_1 /* 8 Bit resolution */
| ADC_CFGR1_CONT /* continues mode */
| ADC_CFGR1_DMAEN; /* enable generation of DMA requests */
//ADC1->SMPR |= ADC_SMPR_SMP_0 | ADC_SMPR_SMP_1 | ADC_SMPR_SMP_2;
//ADC1->SMPR = ADC_SMPR_SMP_1 ;
ADC1->SMPR = ADC_SMPR_SMP_0 | ADC_SMPR_SMP_1 ;
/*
12.5 + 8.5 = 21 ADC Cycles pre ADC sampling
4 MHz / 21 cycle / 256 = 744 Hz
*/
enableADC();
/* conversion will be started automatically with rising edge of TIM2, yet ADSTART is still required */
ADC1->CR |= ADC_CR_ADSTART; /* start the ADC conversion */
/* wait until DMA is completed */
while ( DMA1_Channel1->CNDTR > 0 )
;
}
/*
special values:
-1 Can not find level
255 no rotation
0..254 BMEF level, speed is k*(255-getBEMFLevel())
*/
int getBEMFLevel(uint16_t cnt, uint8_t *buf, uint16_t start)
{
return -1;
}
/*=======================================================================*/
void initTIM(uint16_t tim_cycle)
{
/* enable clock for TIM2 */
RCC->APB1ENR |= RCC_APB1ENR_TIM2EN;
/*enable clock for GPIOA */
RCC->IOPENR |= RCC_IOPENR_IOPAEN; /* Enable clock for GPIO Port A */
__NOP(); /* extra delay for clock stabilization required? */
__NOP();
/* prescalar for AHB and APB1 */
/* reselt defaults for HPRE and PPRE1: no clock division */
// RCC->CFGR &= ~RCC_CFGR_HPRE;
// RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
// RCC->CFGR &= ~RCC_CFGR_PPRE1;
// RCC->CFGR |= RCC_CFGR_PPRE1_DIV1;
/* configure GPIOA PA1 for TIM2 */
GPIOA->MODER &= ~GPIO_MODER_MODE1; /* clear mode for PA9 */
GPIOA->MODER |= GPIO_MODER_MODE1_1; /* alt fn */
GPIOA->OTYPER &= ~GPIO_OTYPER_OT_1; /* push-pull */
GPIOA->AFR[0] &= ~(15<<4); /* Clear Alternate Function PA1 */
GPIOA->AFR[0] |= 2<<4; /* AF2 Alternate Function PA1 */
/* TIM2 configure */
/* disable all interrupts */
//TIM2->DIER = 0; /* 0 is reset default value */
/* clear everything, including the "Update disable" flag, so that updates */
/* are generated */
// TIM2->CR1 = 0; /* 0 is reset default value */
//TIM2->CR1 |= TIM_CR1_ARPE; // ARR is not modified so constant update is ok
/* Update request by manual UG bit setting or slave controller */
/* both is not required here */
/* so, update request by couter over/underflow remains */
//TIM2->CR1 |= TIM_CR1_URS; /* only udf/ovf generae events */
TIM2->CR2 |= TIM_CR2_MMS_1; /* Update event for TRGO */
TIM2->ARR = 5355; /* total cycle count */
TIM2->CCR2 = 1024; /* duty cycle */
//TIM2->CCMR1 &= ~TIM_CCMR1_OC2CE; /* disable clear output compare 2 **/
TIM2->CCMR1 |= TIM_CCMR1_OC2M; /* all 3 bits set: PWM Mode 2 */
//TIM2->CCMR1 &= ~TIM_CCMR1_OC1M_0; /* 110: PWM Mode 1 */
TIM2->CCMR1 |= TIM_CCMR1_OC2PE; /* preload enable CCR2 is preloaded*/
// TIM2->CCMR1 &= ~TIM_CCMR1_OC2FE; /* fast disable (reset default) */
// TIM2->CCMR1 &= ~TIM_CCMR1_CC2S; /* configure cc2 as output (this is reset default) */
//TIM2->EGR |= TIM_EGR_CC2G; /* capture event cc2 */
TIM2->CCER |= TIM_CCER_CC2E; /* set output enable */
//TIM2->CCER |= TIM_CCER_CC2P; /* polarity 0: normal (reset default) / 1: inverted*/
TIM2->PSC = 7; /* divide by 8 */
TIM2->CR1 |= TIM_CR1_CEN; /* counter enable */
/*
TIM2 cycle:
32000000Hz / 5355 / 8 = 747 Hz
*/
}
/*=======================================================================*/
#define BUF_MUL 2
#define TIM_CYCLE_TIME 5355
#define TIM_CYCLE_UPPER_SKIP 100
#define TIM_CYCLE_LOWER_SKIP 400
uint8_t adc_buf[128*BUF_MUL];
void main()
{
uint16_t adc_value;
uint16_t tim_duty;
uint16_t zero_pos;
uint16_t i;
u8g2_uint_t y, yy;
setHSIClock(); /* enable 32 MHz Clock */
startUp(); /* enable systick irq and several power regions */
initDisplay(); /* aktivate display */
initADC();
RCC->IOPENR |= RCC_IOPENR_IOPAEN; /* Enable clock for GPIO Port A */
__NOP();
__NOP();
GPIOA->MODER &= ~GPIO_MODER_MODE1; /* clear mode for PA1 */
GPIOA->MODER |= GPIO_MODER_MODE1_0; /* Output mode for PA1 */
GPIOA->OTYPER &= ~GPIO_OTYPER_OT_1; /* no Push/Pull for PA1 */
GPIOA->OSPEEDR &= ~GPIO_OSPEEDER_OSPEED1; /* low speed for PA1 */
GPIOA->PUPDR &= ~GPIO_PUPDR_PUPD1; /* no pullup/pulldown for PA1 */
GPIOA->BSRR = GPIO_BSRR_BS_1; /* atomic set PA1 */
initTIM(TIM_CYCLE_TIME);
for(;;)
{
u8g2_ClearBuffer(&u8g2);
adc_value = getADC(5);
tim_duty = ((uint32_t)adc_value*((uint32_t)TIM_CYCLE_TIME-TIM_CYCLE_UPPER_SKIP-TIM_CYCLE_LOWER_SKIP))>>8;
tim_duty += TIM_CYCLE_LOWER_SKIP;
TIM2->CCR2 = tim_duty;
TIM2->SR &= ~TIM_SR_UIF;
while( (TIM2->SR & TIM_SR_UIF) == 0 )
;
yy = 30;
for( i = 0; i < 128; i++ )
{
y = 30-(getADC(6)>>3);
u8g2_DrawPixel(&u8g2, i, y);
if ( y < yy )
u8g2_DrawVLine(&u8g2, i, y, yy-y+1);
else
u8g2_DrawVLine(&u8g2, i, yy, y-yy+1);
yy = y;
}
for( i = 0; i < 128*BUF_MUL; i++ )
adc_buf[i] = i;
scanADC(6, 128*BUF_MUL, adc_buf);
yy = 60;
zero_pos = ((uint32_t)tim_duty * (uint32_t)256) / (uint32_t)TIM_CYCLE_TIME;
zero_pos +=4;
zero_pos += (256-zero_pos)>>6;
setRow(10); outHex16(adc_value);
outStr(" "); outHex8(adc_buf[0]); outStr(" "); outHex8(adc_buf[1]); outStr(" "); outHex8(adc_buf[2]);
outStr("|"); outHex8(adc_buf[zero_pos/2]); outStr("|"); outHex8(adc_buf[zero_pos]);
u8g2_DrawVLine(&u8g2, zero_pos/2, yy-7, 15);
u8g2_DrawVLine(&u8g2, zero_pos/4, yy-7, 15);
for( i = 0; i < 128; i++ )
{
y = 60-(adc_buf[i*BUF_MUL]>>3);
u8g2_DrawPixel(&u8g2, i, y);
if ( y < yy )
u8g2_DrawVLine(&u8g2, i, y, yy-y+1);
else
u8g2_DrawVLine(&u8g2, i, yy, y-yy+1);
yy = y;
}
u8g2_SendBuffer(&u8g2);
}
}

View File

@ -0,0 +1,245 @@
/*
stm32l031x6.ld
Modified for stm32l0 from the original nokeep.ld script from the
arm-none-eabi examples by olikraus@gmail.com
Assuming, that the original nokeep.ld file is available under
the GNU General Public License, this file is available under the
same license.
There are three modifications:
1. Provide symbols for the stm32l0 startup code
The following symbols are required for the stm32l0 startup
code (e.g. startup_stm32l031xx.s)
_sidata start address for the initialization values of the .data section
_sdata start address for the .data section. defined in linker script
_edata end address for the .data section. defined in linker script
_sbss start address for the .bss section. defined in linker script
_ebss end address for the .bss section. defined in linker script
_estack top address of the stack
2. Stack size estimation / calculation
_Stack_Size has been added to allow better stack size calculation
3. KEEP keywords
Additionall KEEPs added for .init and .fini. Without this KEEP the
generated code will not work, because of the missing _init function.
4. Bugfix: Allign the end of the flash area
*/
_Stack_Size = 0x400; /* stm32l0: estimated amount of stack */
/* Linker script to configure memory regions.
* Need modifying for a specific board.
* FLASH.ORIGIN: starting address of flash
* FLASH.LENGTH: length of flash
* RAM.ORIGIN: starting address of RAM bank 0
* RAM.LENGTH: length of RAM bank 0
*/
MEMORY
{
FLASH (rx) : ORIGIN = 0x8000000, LENGTH = 32K
RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 8K
}
/* Linker script to place sections and symbol values. Should be used together
* with other linker script that defines memory regions FLASH and RAM.
* It references following symbols, which must be defined in code:
* Reset_Handler : Entry of reset handler
*
* It defines following symbols, which code can use without definition:
* __exidx_start
* __exidx_end
* __copy_table_start__
* __copy_table_end__
* __zero_table_start__
* __zero_table_end__
* __etext
* __data_start__
* __preinit_array_start
* __preinit_array_end
* __init_array_start
* __init_array_end
* __fini_array_start
* __fini_array_end
* __data_end__
* __bss_start__
* __bss_end__
* __end__
* end
* __HeapLimit
* __StackLimit
* __StackTop
* __stack
*/
ENTRY(Reset_Handler)
SECTIONS
{
.text :
{
KEEP(*(.isr_vector))
*(.text*)
/* the st32l0 startup code calls __libc_init_array, which calls the _init */
/* ... sooo.... better keep the init and fini sections */
KEEP ( *(.init) )
KEEP ( *(.fini) )
/* .ctors */
*crtbegin.o(.ctors)
*crtbegin?.o(.ctors)
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors)
*(SORT(.ctors.*))
*(.ctors)
/* .dtors */
*crtbegin.o(.dtors)
*crtbegin?.o(.dtors)
*(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors)
*(SORT(.dtors.*))
*(.dtors)
*(.rodata*)
*(.eh_frame*)
/* allign the end of the flash area */
. = ALIGN(4);
} > FLASH
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > FLASH
__exidx_start = .;
.ARM.exidx :
{
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
} > FLASH
__exidx_end = .;
/* To copy multiple ROM to RAM sections,
* uncomment .copy.table section and,
* define __STARTUP_COPY_MULTIPLE in startup_ARMCMx.S */
/*
.copy.table :
{
. = ALIGN(4);
__copy_table_start__ = .;
LONG (__etext)
LONG (__data_start__)
LONG (__data_end__ - __data_start__)
LONG (__etext2)
LONG (__data2_start__)
LONG (__data2_end__ - __data2_start__)
__copy_table_end__ = .;
} > FLASH
*/
/* To clear multiple BSS sections,
* uncomment .zero.table section and,
* define __STARTUP_CLEAR_BSS_MULTIPLE in startup_ARMCMx.S */
/*
.zero.table :
{
. = ALIGN(4);
__zero_table_start__ = .;
LONG (__bss_start__)
LONG (__bss_end__ - __bss_start__)
LONG (__bss2_start__)
LONG (__bss2_end__ - __bss2_start__)
__zero_table_end__ = .;
} > FLASH
*/
__etext = .;
_sidata = .; /* for stm32l0 startup code */
.data : AT (__etext)
{
__data_start__ = .;
_sdata = .; /* for stm32l0 startup code */
*(vtable)
*(.data*)
. = ALIGN(4);
/* preinit data */
PROVIDE_HIDDEN (__preinit_array_start = .);
*(.preinit_array)
PROVIDE_HIDDEN (__preinit_array_end = .);
. = ALIGN(4);
/* init data */
PROVIDE_HIDDEN (__init_array_start = .);
*(SORT(.init_array.*))
*(.init_array)
PROVIDE_HIDDEN (__init_array_end = .);
. = ALIGN(4);
/* finit data */
PROVIDE_HIDDEN (__fini_array_start = .);
*(SORT(.fini_array.*))
*(.fini_array)
PROVIDE_HIDDEN (__fini_array_end = .);
*(.jcr)
. = ALIGN(4);
/* All data end */
__data_end__ = .;
_edata = .; /* for stm32l0 startup code */
} > RAM
.bss :
{
. = ALIGN(4);
__bss_start__ = .;
_sbss = .; /* for stm32l0 startup code */
*(.bss*)
*(COMMON)
. = ALIGN(4);
__bss_end__ = .;
_ebss = .; /* for stm32l0 startup code */
} > RAM
.heap (COPY):
{
__end__ = .;
PROVIDE(end = .);
*(.heap*)
__HeapLimit = .;
} > RAM
/* .stack_dummy section doesn't contains any symbols. It is only
* used for linker to calculate size of stack sections, and assign
* values to stack symbols later */
.stack_dummy (COPY):
{
*(.stack*)
. = . + _Stack_Size; /* estimated stack size */
} > RAM
/* Set stack top to end of RAM, and stack limit move down by
* size of stack_dummy section */
__StackTop = ORIGIN(RAM) + LENGTH(RAM);
_estack = __StackTop; /* for stm32l0 startup code */
__StackLimit = __StackTop - SIZEOF(.stack_dummy);
PROVIDE(__stack = __StackTop);
/* Check if data + heap + stack exceeds RAM limit */
ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed with stack")
}

View File

@ -0,0 +1,112 @@
/*
u8x8cb.c
STM32L031
PA13: Clock
PA14: Data
Both lines have a pullup resistor
*/
#include "stm32l031xx.h"
#include "delay.h"
#include "u8x8.h"
uint8_t u8x8_gpio_and_delay_stm32l0(u8x8_t *u8x8, uint8_t msg, uint8_t arg_int, void *arg_ptr)
{
switch(msg)
{
case U8X8_MSG_GPIO_AND_DELAY_INIT:
/* only support for software I2C*/
RCC->IOPENR |= RCC_IOPENR_IOPAEN; /* Enable clock for GPIO Port A */
__NOP();
__NOP();
GPIOA->MODER &= ~GPIO_MODER_MODE14; /* clear mode for PA10 */
//GPIOA->MODER |= GPIO_MODER_MODE14_0; /* Output mode for PA10 */
GPIOA->OTYPER &= ~GPIO_OTYPER_OT_14; /* no open drain for PA10 */
GPIOA->OSPEEDR &= ~GPIO_OSPEEDER_OSPEED14; /* low speed for PA10 */
GPIOA->PUPDR &= ~GPIO_PUPDR_PUPD14; /* no pullup/pulldown for PA10 */
//GPIOA->BSRR = GPIO_BSRR_BS_14; /* atomic set PA10 */
GPIOA->MODER &= ~GPIO_MODER_MODE13; /* clear mode for PA9 */
//GPIOA->MODER |= GPIO_MODER_MODE13_0; /* Output mode for PA9 */
GPIOA->OTYPER &= ~GPIO_OTYPER_OT_13; /* no open drain for PA9 */
GPIOA->OSPEEDR &= ~GPIO_OSPEEDER_OSPEED13; /* low speed for PA9 */
GPIOA->PUPDR &= ~GPIO_PUPDR_PUPD13; /* no pullup/pulldown for PA9 */
//GPIOA->BSRR = GPIO_BSRR_BS_13; /* atomic set PA9 */
break;
case U8X8_MSG_DELAY_NANO:
/* not required for SW I2C */
break;
case U8X8_MSG_DELAY_10MICRO:
/* not used at the moment */
break;
case U8X8_MSG_DELAY_100NANO:
/* not used at the moment */
break;
case U8X8_MSG_DELAY_MILLI:
delay_micro_seconds(arg_int*1000UL);
break;
case U8X8_MSG_DELAY_I2C:
/* arg_int is 1 or 4: 100KHz (5us) or 400KHz (1.25us) */
delay_micro_seconds(arg_int<=2?5:1);
break;
case U8X8_MSG_GPIO_I2C_CLOCK:
if ( arg_int == 0 )
{
GPIOA->MODER &= ~GPIO_MODER_MODE13; /* clear mode for PA10 */
GPIOA->MODER |= GPIO_MODER_MODE13_0; /* Output mode for PA10 */
GPIOA->BSRR = GPIO_BSRR_BR_3; /* atomic clr PA9 */
}
else
{
//GPIOA->BSRR = GPIO_BSRR_BS_13; /* atomic set PA9 */
GPIOA->MODER &= ~GPIO_MODER_MODE13; /* clear mode for PA9: input mode */
}
break;
case U8X8_MSG_GPIO_I2C_DATA:
if ( arg_int == 0 )
{
GPIOA->MODER &= ~GPIO_MODER_MODE14; /* clear mode for PA10 */
GPIOA->MODER |= GPIO_MODER_MODE14_0; /* Output mode for PA10 */
GPIOA->BSRR = GPIO_BSRR_BR_14; /* atomic clr PA10 */
}
else
{
//GPIOA->BSRR = GPIO_BSRR_BS_14; /* atomic set PA10 */
// input mode
GPIOA->MODER &= ~GPIO_MODER_MODE14; /* clear mode for PA10: input mode */
}
break;
/*
case U8X8_MSG_GPIO_MENU_SELECT:
u8x8_SetGPIOResult(u8x8, Chip_GPIO_GetPinState(LPC_GPIO, KEY_SELECT_PORT, KEY_SELECT_PIN));
break;
case U8X8_MSG_GPIO_MENU_NEXT:
u8x8_SetGPIOResult(u8x8, Chip_GPIO_GetPinState(LPC_GPIO, KEY_NEXT_PORT, KEY_NEXT_PIN));
break;
case U8X8_MSG_GPIO_MENU_PREV:
u8x8_SetGPIOResult(u8x8, Chip_GPIO_GetPinState(LPC_GPIO, KEY_PREV_PORT, KEY_PREV_PIN));
break;
case U8X8_MSG_GPIO_MENU_HOME:
u8x8_SetGPIOResult(u8x8, Chip_GPIO_GetPinState(LPC_GPIO, KEY_HOME_PORT, KEY_HOME_PIN));
break;
*/
default:
u8x8_SetGPIOResult(u8x8, 1);
break;
}
return 1;
}

View File

@ -4,6 +4,7 @@
Example for the STM32L031 Eval Board with 128x64 OLED at PA13/PA14
Single Mosfet Shield
MOSFET: PA1 / AF2: TIM2_CH2
VarRes: PA5 / ADC CH5
Voltage sense: PA6 / ADC CH6