diff options
author | jaseg <git@jaseg.net> | 2020-03-23 01:07:19 +0100 |
---|---|---|
committer | jaseg <git@jaseg.net> | 2020-03-23 01:07:19 +0100 |
commit | 6ea56ed6ceacd990e0255d592032af4bd84f7cd6 (patch) | |
tree | fa432bc57eb2fcf5607a0e3bbf0b839d0d1637fe /fw | |
download | lampomatic-6ea56ed6ceacd990e0255d592032af4bd84f7cd6.tar.gz lampomatic-6ea56ed6ceacd990e0255d592032af4bd84f7cd6.tar.bz2 lampomatic-6ea56ed6ceacd990e0255d592032af4bd84f7cd6.zip |
foo
Diffstat (limited to 'fw')
-rw-r--r-- | fw/Makefile | 73 | ||||
-rw-r--r-- | fw/base.c | 28 | ||||
-rw-r--r-- | fw/cmsis_exports.c | 48 | ||||
-rw-r--r-- | fw/gen_cmsis_exports.py | 30 | ||||
-rw-r--r-- | fw/global.h | 58 | ||||
-rw-r--r-- | fw/i2c.c | 236 | ||||
-rw-r--r-- | fw/i2c.h | 107 | ||||
-rw-r--r-- | fw/ina226.c | 75 | ||||
-rw-r--r-- | fw/ina226.h | 108 | ||||
-rw-r--r-- | fw/lcd1602.c | 187 | ||||
-rw-r--r-- | fw/lcd1602.h | 98 | ||||
-rw-r--r-- | fw/mac.c | 3 | ||||
-rw-r--r-- | fw/mac.h | 22 | ||||
-rw-r--r-- | fw/main.c | 502 | ||||
-rw-r--r-- | fw/mcp9801.c | 42 | ||||
-rw-r--r-- | fw/mcp9801.h | 66 | ||||
-rw-r--r-- | fw/mini-printf.c | 208 | ||||
-rw-r--r-- | fw/mini-printf.h | 50 | ||||
-rw-r--r-- | fw/openocd.cfg | 14 | ||||
-rw-r--r-- | fw/serial.c | 233 | ||||
-rw-r--r-- | fw/serial.h | 62 | ||||
-rw-r--r-- | fw/startup_stm32f030x6.s | 273 | ||||
-rw-r--r-- | fw/stm32_flash.ld | 136 | ||||
-rw-r--r-- | fw/system_stm32f0xx.c | 336 |
24 files changed, 2995 insertions, 0 deletions
diff --git a/fw/Makefile b/fw/Makefile new file mode 100644 index 0000000..6608789 --- /dev/null +++ b/fw/Makefile @@ -0,0 +1,73 @@ +CUBE_PATH ?= $(wildcard ~)/resource/STM32Cube_FW_F0_V1.9.0 +CMSIS_PATH ?= $(CUBE_PATH)/Drivers/CMSIS +CMSIS_DEV_PATH ?= $(CMSIS_PATH)/Device/ST/STM32F0xx +HAL_PATH ?= $(CUBE_PATH)/Drivers/STM32F0xx_HAL_Driver + +MAC_ADDR ?= 0xdeadbeef + +CC := arm-none-eabi-gcc +LD := arm-none-eabi-ld +OBJCOPY := arm-none-eabi-objcopy +OBJDUMP := arm-none-eabi-objdump +SIZE := arm-none-eabi-size + +CFLAGS = -g -Wall -std=gnu11 -O0 -fdump-rtl-expand -Wno-discarded-qualifiers +CFLAGS += -mlittle-endian -mcpu=cortex-m0 -mthumb +#CFLAGS += -ffunction-sections -fdata-sections +LDFLAGS = -nostartfiles +#LDFLAGS += -specs=rdimon.specs -DSEMIHOSTING +LDFLAGS += -Wl,-Map=main.map -nostdlib +#LDFLAGS += -Wl,--gc-sections +LIBS = -lgcc +#LIBS += -lrdimon + +# Technically we're using an STM32F030F4, but apart from the TSSOP20 package that one is largely identical to the +# STM32F030*6 and there is no separate device header provided for it, so we're faking a *6 device here. This is +# even documented in stm32f0xx.h. Thanks ST! +CFLAGS += -DSTM32F030x6 -DHSE_VALUE=8000000 -DMAC_ADDR=$(MAC_ADDR) + +LDFLAGS += -Tstm32_flash.ld +CFLAGS += -I$(CMSIS_DEV_PATH)/Include -I$(CMSIS_PATH)/Include -I$(HAL_PATH)/Inc -Iconfig -I../common +#LDFLAGS += -L$(CMSIS_PATH)/Lib/GCC -larm_cortexM0l_math + +SOURCES = main.c startup_stm32f030x6.s system_stm32f0xx.c base.c $(HAL_PATH)/Src/stm32f0xx_ll_utils.c cmsis_exports.c \ + i2c.c lcd1602.c mini-printf.c + +################################################### + +.PHONY: program clean + +all: main.elf + +.clang: + echo flags = $(CFLAGS) > .clang + +cmsis_exports.c: $(CMSIS_DEV_PATH)/Include/stm32f030x6.h $(CMSIS_PATH)/Include/core_cm0.h + python3 gen_cmsis_exports.py $^ > $@ + +%.o: %.c + $(CC) -c $(CFLAGS) -o $@ $^ +# $(CC) -E $(CFLAGS) -o $(@:.o=.pp) $^ + +%.o: %.s + $(CC) -c $(CFLAGS) -o $@ $^ +# $(CC) -E $(CFLAGS) -o $(@:.o=.pp) $^ + +%.dot: %.elf + r2 -a arm -qc 'aa;agC' $< 2>/dev/null >$@ + +main.elf: $(SOURCES) + $(CC) $(CFLAGS) $(LDFLAGS) -o $@ $^ $(LIBS) + $(OBJCOPY) -O ihex $@ $(@:.elf=.hex) + $(OBJCOPY) -O binary $@ $(@:.elf=.bin) + $(OBJDUMP) -St $@ >$(@:.elf=.lst) + $(SIZE) $@ + +program: main.elf openocd.cfg + openocd -f openocd.cfg -c "program $< verify reset exit" + +clean: + rm -f **.o **.pp + rm -f main.elf main.hex main.bin main.map main.lst + rm -f **.expand + diff --git a/fw/base.c b/fw/base.c new file mode 100644 index 0000000..75befcb --- /dev/null +++ b/fw/base.c @@ -0,0 +1,28 @@ + +#include <unistd.h> + +int __errno = 0; +void *_impure_ptr = NULL; + +void __sinit(void) { +} + +void *memset(void *s, int c, size_t n) { + char *end = (char *)s + n; + for (char *p = (char *)s; p < end; p++) + *p = (char)c; + return s; +} + +size_t strlen(const char *s) { + const char *start = s; + while (*s++); + return s - start - 1; +} + +char *strcpy(char *dst, const char *src) { + char *p = dst; + while (*src) + *p++ = *src++; + return dst; +} diff --git a/fw/cmsis_exports.c b/fw/cmsis_exports.c new file mode 100644 index 0000000..39874b5 --- /dev/null +++ b/fw/cmsis_exports.c @@ -0,0 +1,48 @@ +#ifndef __GENERATED_CMSIS_HEADER_EXPORTS__ +#define __GENERATED_CMSIS_HEADER_EXPORTS__ + +#include <stm32f030x6.h> + +/* stm32f030x6.h */ +TIM_TypeDef *tim3 = TIM3; +TIM_TypeDef *tim14 = TIM14; +RTC_TypeDef *rtc = RTC; +WWDG_TypeDef *wwdg = WWDG; +IWDG_TypeDef *iwdg = IWDG; +I2C_TypeDef *i2c1 = I2C1; +PWR_TypeDef *pwr = PWR; +SYSCFG_TypeDef *syscfg = SYSCFG; +EXTI_TypeDef *exti = EXTI; +ADC_TypeDef *adc1 = ADC1; +ADC_Common_TypeDef *adc1_common = ADC1_COMMON; +ADC_Common_TypeDef *adc = ADC; +TIM_TypeDef *tim1 = TIM1; +SPI_TypeDef *spi1 = SPI1; +USART_TypeDef *usart1 = USART1; +TIM_TypeDef *tim16 = TIM16; +TIM_TypeDef *tim17 = TIM17; +DBGMCU_TypeDef *dbgmcu = DBGMCU; +DMA_TypeDef *dma1 = DMA1; +DMA_Channel_TypeDef *dma1_channel1 = DMA1_Channel1; +DMA_Channel_TypeDef *dma1_channel2 = DMA1_Channel2; +DMA_Channel_TypeDef *dma1_channel3 = DMA1_Channel3; +DMA_Channel_TypeDef *dma1_channel4 = DMA1_Channel4; +DMA_Channel_TypeDef *dma1_channel5 = DMA1_Channel5; +FLASH_TypeDef *flash = FLASH; +OB_TypeDef *ob = OB; +RCC_TypeDef *rcc = RCC; +CRC_TypeDef *crc = CRC; +GPIO_TypeDef *gpioa = GPIOA; +GPIO_TypeDef *gpiob = GPIOB; +GPIO_TypeDef *gpioc = GPIOC; +GPIO_TypeDef *gpiod = GPIOD; +GPIO_TypeDef *gpiof = GPIOF; + +#include <core_cm0.h> + +/* core_cm0.h */ +SCB_Type *scb = SCB; +SysTick_Type *systick = SysTick; +NVIC_Type *nvic = NVIC; + +#endif//__GENERATED_CMSIS_HEADER_EXPORTS__ diff --git a/fw/gen_cmsis_exports.py b/fw/gen_cmsis_exports.py new file mode 100644 index 0000000..ba3422b --- /dev/null +++ b/fw/gen_cmsis_exports.py @@ -0,0 +1,30 @@ +#!/usr/bin/env python3 +import re +import os + +if __name__ == '__main__': + import argparse + + parser = argparse.ArgumentParser() + parser.add_argument('cmsis_device_header', nargs='+', type=argparse.FileType('rb')) + args = parser.parse_args() + + print('#ifndef __GENERATED_CMSIS_HEADER_EXPORTS__') + print('#define __GENERATED_CMSIS_HEADER_EXPORTS__') + print() + for header in args.cmsis_device_header: + lines = header.readlines() + name = os.path.basename(header.name) + print('#include <{}>'.format(name)) + print() + + print('/* {} */'.format(name)) + for l in lines: + match = re.match(b'^#define (\w+)\s+\W*(\w+_TypeDef|\w+_Type).*$', l) + if match: + inst, typedef = match.groups() + inst, typedef = inst.decode(), typedef.decode() + print('{} *{} = {};'.format(typedef, inst.lower(), inst)) + print() + print('#endif//__GENERATED_CMSIS_HEADER_EXPORTS__') + diff --git a/fw/global.h b/fw/global.h new file mode 100644 index 0000000..4753543 --- /dev/null +++ b/fw/global.h @@ -0,0 +1,58 @@ +/* Megumin LED display firmware + * Copyright (C) 2018 Sebastian Götte <code@jaseg.net> + * + * 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 3 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, see <http://www.gnu.org/licenses/>. + */ + +#ifndef __GLOBAL_H__ +#define __GLOBAL_H__ + +/* Workaround for sub-par ST libraries */ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wstrict-aliasing" +#include <stm32f0xx.h> +#include <stm32f0xx_ll_utils.h> +#include <stm32f0xx_ll_spi.h> +#pragma GCC diagnostic pop + +#include <system_stm32f0xx.h> + +#include <stdint.h> +#include <stdbool.h> +#include <string.h> +#include <unistd.h> + +/* Microcontroller part number: STM32F030F4P6 */ + +/* Things used for module status reporting. */ +#define FIRMWARE_VERSION 1 +#define HARDWARE_VERSION 3 + +#define TS_CAL1 (*(uint16_t *)0x1FFFF7B8) +#define VREFINT_CAL (*(uint16_t *)0x1FFFF7BA) + +#define STATUS_LED_DURATION_MS 200 +#define TICK_MS 10 + +extern volatile unsigned int sys_time_tick; +extern volatile unsigned int sys_time_ms; +extern volatile unsigned int sys_time_s; +extern unsigned int frame_duration_us; + +extern volatile uint8_t global_brightness; + +void trigger_error_led(void); +void trigger_comm_led(void); + +#endif/*__GLOBAL_H__*/ diff --git a/fw/i2c.c b/fw/i2c.c new file mode 100644 index 0000000..bab1a16 --- /dev/null +++ b/fw/i2c.c @@ -0,0 +1,236 @@ +// Inter-integrated circuit (I2C) management
+
+
+#include "i2c.h"
+
+
+// I2C timeout, about 2ms
+#define I2C_TIMEOUT 200U
+
+// Maximum NBYTES value
+#define I2C_NBYTES_MAX 255U
+
+
+// Count rough delay for timeouts
+static uint32_t i2c_calc_delay(uint32_t delay) {
+ uint32_t cnt;
+
+ if (SystemCoreClock > 1000000U) {
+ cnt = (delay * ((SystemCoreClock / 1000000U) + 1U));
+ } else {
+ cnt = (((delay / 100U) + 1U) * ((SystemCoreClock / 10000U) + 1U));
+ }
+
+ return cnt;
+}
+
+// Check if target device is ready for communication
+// input:
+// I2Cx - pointer to the I2C peripheral (I2C1, etc.)
+// devAddr - target device address
+// trials - number of trials (must not be zero)
+// return:
+// I2C_ERROR if there was a timeout during I2C operations, I2C_SUCCESS otherwise
+I2CSTATUS i2c_is_device_ready(I2C_TypeDef* I2Cx, uint8_t devAddr, uint32_t trials) {
+ volatile uint32_t wait;
+ uint32_t delay_val = i2c_calc_delay(I2C_TIMEOUT);
+ uint32_t reg;
+
+ while (trials--) {
+ // Clear all flags
+ I2Cx->ICR = I2C_ICR_ALL;
+
+ // Generate START
+ i2c_genstart(I2Cx, devAddr);
+
+ // Wait for STOP, NACK or BERR
+ wait = delay_val;
+ while (!((reg = I2Cx->ISR) & (I2C_ISR_STOPF | I2C_ISR_NACKF | I2C_ISR_BERR)) && --wait);
+ if (wait == 0) { return I2C_ERROR; }
+
+ // Wait while STOP flag is reset
+ wait = delay_val;
+ while (!(I2Cx->ISR & I2C_ISR_STOPF) && --wait);
+ if (wait == 0) { return I2C_ERROR; }
+
+ // Clear the NACK, STOP and BERR flags
+ I2Cx->ICR = I2C_ICR_STOPCF | I2C_ICR_NACKCF | I2C_ICR_BERRCF;
+
+ // Check for BERR flag
+ if (reg & I2C_ISR_BERR) {
+ // Misplaced START/STOP? Perform a software reset of I2C
+ i2c_disable(I2Cx);
+ i2c_enable(I2Cx);
+ } else {
+ // Device responded if NACK flag is not set
+ if (!(reg & I2C_ISR_NACKF)) { return I2C_SUCCESS; }
+ }
+ }
+
+ return I2C_ERROR;
+}
+
+// Transmit an amount of data in master mode
+// input:
+// I2Cx - pointer to the I2C peripheral (I2C1, etc.)
+// pBbuf - pointer to the data buffer
+// nbytes - number of bytes to transmit
+// devAddr - address of target device
+// flags - options for transmission, combination of I2C_TX_xx values:
+// I2C_TX_NOSTART - don't generate START condition
+// I2C_TX_NOSTOP - don't generate STOP condition
+// I2C_TX_CONT - this flag indicates that transmission will be continued
+// e.g. by calling this function again with NOSTART flag
+// zero value - generate both START and STOP conditions
+// return:
+// I2C_ERROR if there was a timeout during I2C operations, I2C_SUCCESS otherwise
+I2CSTATUS i2c_transmit(I2C_TypeDef* I2Cx, const uint8_t *pBuf, uint32_t nbytes, uint8_t devAddr, uint32_t flags) {
+ uint32_t reg;
+ uint32_t tx_count;
+ uint32_t delay_val = i2c_calc_delay(I2C_TIMEOUT);
+ volatile uint32_t wait;
+
+ // Clear all flags
+ I2Cx->ICR = I2C_ICR_ALL;
+
+ // Everything regarding to the transmission is in the CR2 register
+ reg = I2Cx->CR2;
+ reg &= ~I2C_CR2_ALL;
+
+ // Slave device address
+ reg |= (devAddr & I2C_CR2_SADD);
+
+ // Whether it need to generate START condition
+ if (!(flags & I2C_TX_NOSTART)) { reg |= I2C_CR2_START; }
+
+ // Whether it need to generate STOP condition
+ if ((flags & I2C_TX_CONT) || (nbytes > I2C_NBYTES_MAX)) {
+ reg |= I2C_CR2_RELOAD;
+ } else {
+ if (!(flags & I2C_TX_NOSTOP)) { reg |= I2C_CR2_AUTOEND; }
+ }
+
+ // Transfer length
+ tx_count = (nbytes > I2C_NBYTES_MAX) ? I2C_NBYTES_MAX : nbytes;
+ nbytes -= tx_count;
+ reg |= tx_count << I2C_CR2_NBYTES_Pos;
+
+ // Write a composed value to the I2C register
+ I2Cx->CR2 = reg;
+
+ // Transmit data
+ while (tx_count) {
+ // Wait until either TXIS or NACK flag is set
+ wait = delay_val;
+ while (!((reg = I2Cx->ISR) & (I2C_ISR_TXIS | I2C_ISR_NACKF)) && --wait);
+ if ((reg & I2C_ISR_NACKF) || (wait == 0)) { return I2C_ERROR; }
+
+ // Transmit byte
+ I2Cx->TXDR = *pBuf++;
+ tx_count--;
+
+ if ((tx_count == 0) && (nbytes != 0)) {
+ // Wait until TCR flag is set (Transfer Complete Reload)
+ wait = delay_val;
+ while (!(I2Cx->ISR & I2C_ISR_TCR) && --wait);
+ if (wait == 0) { return I2C_ERROR; }
+
+ // Configure next (or last) portion transfer
+ reg = I2Cx->CR2;
+ reg &= ~(I2C_CR2_NBYTES | I2C_CR2_RELOAD | I2C_CR2_AUTOEND);
+ if ((flags & I2C_TX_CONT) || (nbytes > I2C_NBYTES_MAX)) {
+ reg |= I2C_CR2_RELOAD;
+ } else {
+ if (!(flags & I2C_TX_NOSTOP)) { reg |= I2C_CR2_AUTOEND; }
+ }
+ tx_count = (nbytes > I2C_NBYTES_MAX) ? I2C_NBYTES_MAX : nbytes;
+ nbytes -= tx_count;
+ reg |= tx_count << I2C_CR2_NBYTES_Pos;
+ I2Cx->CR2 = reg;
+ }
+ }
+
+ // End of transmission
+ wait = delay_val;
+ while (!(I2Cx->ISR & (I2C_ISR_TC | I2C_ISR_TCR | I2C_ISR_STOPF)) && --wait);
+
+ return (wait) ? I2C_SUCCESS : I2C_ERROR;
+}
+
+// Receive an amount of data in master mode
+// input:
+// I2Cx - pointer to the I2C peripheral (I2C1, etc.)
+// buf - pointer to the data buffer
+// nbytes - number of bytes to receive
+// devAddr - address of target device
+// return:
+// I2C_ERROR if there was a timeout during I2C operations, I2C_SUCCESS otherwise
+I2CSTATUS i2c_receive(I2C_TypeDef* I2Cx, uint8_t *pBuf, uint32_t nbytes, uint8_t devAddr) {
+ uint32_t reg;
+ uint32_t rx_count;
+ uint32_t delay_val = i2c_calc_delay(I2C_TIMEOUT);
+ volatile uint32_t wait;
+
+ // Clear all flags
+ I2Cx->ICR = I2C_ICR_ALL;
+
+ // Everything regarding to the transmission is in the CR2 register
+ reg = I2Cx->CR2;
+ reg &= ~I2C_CR2_ALL;
+
+ // Configure slave device address, enable START condition and set direction to READ
+ reg |= (devAddr & I2C_CR2_SADD) | I2C_CR2_START | I2C_CR2_RD_WRN;
+
+ // Transfer length
+ if (nbytes > I2C_NBYTES_MAX) {
+ rx_count = I2C_NBYTES_MAX;
+ reg |= I2C_CR2_RELOAD;
+ } else {
+ rx_count = nbytes;
+ reg |= I2C_CR2_AUTOEND;
+ }
+ reg |= rx_count << I2C_CR2_NBYTES_Pos;
+ nbytes -= rx_count;
+
+ // Write a composed value to the I2C register
+ I2Cx->CR2 = reg;
+
+ // Receive data
+ while (rx_count) {
+ // Wait until either RXNE or NACK flag is set
+ wait = delay_val;
+ while (!((reg = I2Cx->ISR) & (I2C_ISR_RXNE | I2C_ISR_NACKF)) && --wait);
+ if ((reg & I2C_ISR_NACKF) || (wait == 0)) { return I2C_ERROR; }
+
+ // Read received data
+ *pBuf++ = I2Cx->RXDR;
+ rx_count--;
+
+ if ((rx_count == 0) && (nbytes != 0)) {
+ // Wait until TCR flag is set (Transfer Complete Reload)
+ wait = delay_val;
+ while (!(I2Cx->ISR & I2C_ISR_TCR) && --wait);
+ if (wait == 0) { return I2C_ERROR; }
+
+ // Configure next (or last) portion transfer
+ reg = I2Cx->CR2;
+ reg &= ~(I2C_CR2_NBYTES | I2C_CR2_AUTOEND | I2C_CR2_RELOAD);
+ if (nbytes > I2C_NBYTES_MAX) {
+ rx_count = I2C_NBYTES_MAX;
+ reg |= I2C_CR2_RELOAD;
+ } else {
+ rx_count = nbytes;
+ reg |= I2C_CR2_AUTOEND;
+ }
+ reg |= rx_count << I2C_CR2_NBYTES_Pos;
+ nbytes -= rx_count;
+ I2Cx->CR2 = reg;
+ }
+ }
+
+ // Wait for the STOP flag
+ wait = delay_val;
+ while (!(I2Cx->ISR & I2C_ISR_STOPF) && --wait);
+
+ return (wait) ? I2C_SUCCESS : I2C_ERROR;
+}
diff --git a/fw/i2c.h b/fw/i2c.h new file mode 100644 index 0000000..4df7750 --- /dev/null +++ b/fw/i2c.h @@ -0,0 +1,107 @@ +#ifndef __I2C_H
+#define __I2C_H
+
+#include "global.h"
+
+// Definitions of I2C analog filter state
+#define I2C_AF_ENABLE ((uint32_t)0x00000000U) // Analog filter is enabled
+#define I2C_AF_DISABLE I2C_CR1_ANFOFF // Analog filter is disabled
+
+// Flags definitions for transmit function
+#define I2C_TX_STOP ((uint32_t)0x00000000U) // Generate STOP condition
+#define I2C_TX_NOSTOP ((uint32_t)0x10000000U) // Don't generate STOP condition
+#define I2C_TX_NOSTART ((uint32_t)0x20000000U) // Don't generate START condition
+#define I2C_TX_CONT ((uint32_t)0x40000000U) // The transmission will be continued
+// Definitions for compatibility with old code using this library
+#define I2C_GENSTOP_YES I2C_TX_STOP
+#define I2C_GENSTOP_NO I2C_TX_NOSTOP
+
+// Definition of bits to reset in CR2 register
+#define I2C_CR2_ALL (I2C_CR2_SADD | \
+ I2C_CR2_NBYTES | \
+ I2C_CR2_RELOAD | \
+ I2C_CR2_AUTOEND | \
+ I2C_CR2_RD_WRN | \
+ I2C_CR2_START | \
+ I2C_CR2_STOP)
+
+// Definition of all bits in ICR register (clear all I2C flags at once)
+#define I2C_ICR_ALL (I2C_ICR_ADDRCF | \
+ I2C_ICR_ALERTCF | \
+ I2C_ICR_ARLOCF | \
+ I2C_ICR_BERRCF | \
+ I2C_ICR_NACKCF | \
+ I2C_ICR_OVRCF | \
+ I2C_ICR_PECCF | \
+ I2C_ICR_STOPCF | \
+ I2C_ICR_TIMOUTCF)
+
+
+// Result of I2C functions
+typedef enum {
+ I2C_ERROR = 0,
+ I2C_SUCCESS = !I2C_ERROR
+} I2CSTATUS;
+
+
+// Public functions and macros
+
+// Enable I2C peripheral
+// input:
+// I2Cx - pointer to the I2C peripheral (I2C1, etc.)
+static inline void i2c_enable(I2C_TypeDef* I2Cx) {
+ I2Cx->CR1 |= I2C_CR1_PE;
+}
+
+// Disable I2C peripheral
+// input:
+// I2Cx - pointer to the I2C peripheral (I2C1, etc.)
+static inline void i2c_disable(I2C_TypeDef* I2Cx) {
+ I2Cx->CR1 &= ~I2C_CR1_PE;
+}
+
+// Configure I2C noise filters
+// input:
+// I2Cx - pointer to the I2C peripheral (I2C1, etc.)
+// af - analog filter state, I2C_AF_DISABLE or I2C_AF_ENABLE
+// df - digital filter configuration, can be a value in range from 0 to 15
+// zero value means the digital filter is disabled
+// this values means filtering capability up to (df * ti2cclk)
+// note: must be called only when I2C is disabled (PE bit in I2C_CR1 register is reset)
+static inline void i2c_config_filters(I2C_TypeDef* I2Cx, uint32_t af, uint32_t df) {
+ I2Cx->CR1 &= ~(I2C_CR1_ANFOFF | I2C_CR1_DNF);
+ I2Cx->CR1 |= (af & I2C_CR1_ANFOFF) | ((df << I2C_CR1_DNF_Pos) & I2C_CR1_DNF);
+}
+
+// Configure the I2C timings (SDA setup/hold time and SCL high/low period)
+// input:
+// I2Cx - pointer to the I2C peripheral (I2C1, etc.)
+// timing - the value for I2C_TIMINGR register
+// note: must be called only when I2C is disabled (PE bit in I2C_CR1 register is reset)
+static inline void i2c_config_timing(I2C_TypeDef* I2Cx, uint32_t timing) {
+ I2Cx->TIMINGR = timing;
+}
+
+// Generate START condition
+// input:
+// I2Cx - pointer to the I2C peripheral (I2C1, etc.)
+// addr - I2C device address
+// note: 7-bit addressing mode
+static inline void i2c_genstart(I2C_TypeDef* I2Cx, uint32_t addr) {
+ I2Cx->CR2 = (addr & I2C_CR2_SADD) | I2C_CR2_START | I2C_CR2_AUTOEND;
+}
+
+// Generate STOP condition
+// input:
+// I2Cx - pointer to the I2C peripheral (I2C1, etc.)
+static inline void i2c_genstop(I2C_TypeDef* I2Cx) {
+ I2Cx->CR2 |= I2C_CR2_STOP;
+}
+
+
+// Function prototypes
+I2CSTATUS i2c_is_device_ready(I2C_TypeDef* I2Cx, uint8_t devAddr, uint32_t Trials);
+I2CSTATUS i2c_transmit(I2C_TypeDef* I2Cx, const uint8_t *pBuf, uint32_t nbytes, uint8_t devAddr, uint32_t flags);
+I2CSTATUS i2c_receive(I2C_TypeDef* I2Cx, uint8_t *pBuf, uint32_t nbytes, uint8_t devAddr);
+
+#endif // __I2C_H
diff --git a/fw/ina226.c b/fw/ina226.c new file mode 100644 index 0000000..6768c3b --- /dev/null +++ b/fw/ina226.c @@ -0,0 +1,75 @@ + +#include "global.h" +#include "i2c.h" +#include "ina226.h" + +void ina226_init(struct ina226 *dev, I2C_TypeDef *i2c_periph, uint8_t i2c_addr, uint16_t rs_uOhm, uint16_t conv_config) { + dev->i2c_periph = i2c_periph; + dev->i2c_addr = i2c_addr; + + dev->conv_config = conv_config; + dev->rs_uOhm = rs_uOhm; + dev->i_lsb_uA = INA226_VS_LSB_nV * 1000 / rs_uOhm; + + uint16_t cal = 5120000 / dev->i_lsb_uA * 1000 / dev->rs_uOhm; + ina226_write_reg(dev, INA226_REG_CAL, cal); + dev->conv_ready = false; + + /* Do not trigger a conversion yet since depending on settings a conversion might take a long time, and we don't + * want to immediately block the device after initialization. */ +} + +void ina226_trigger(struct ina226 *dev, int mode) { + ina226_write_reg(dev, INA226_REG_CONFIG, + dev->conv_config | mode | INA226_CONFIG_MODE_TRIG); + dev->conv_ready = false; +} + +void ina226_write_reg(struct ina226 *dev, uint8_t reg, uint16_t val) { + uint8_t buf[3] = { reg, val>>8, val&0xff }; + i2c_transmit(dev->i2c_periph, buf, sizeof(buf), dev->i2c_addr, I2C_GENSTOP_YES); +} + +uint16_t ina226_read_reg(struct ina226 *dev, uint8_t reg) { + uint8_t buf2[1] = { reg }; + i2c_transmit(dev->i2c_periph, buf2, sizeof(buf2), dev->i2c_addr, I2C_GENSTOP_NO); + uint8_t rx[2]; + i2c_receive(dev->i2c_periph, rx, sizeof(rx), dev->i2c_addr); + return (rx[0]<<8) | rx[1]; +} + +int ina226_read_raw(struct ina226 *dev, int16_t *I_raw, int16_t *V_raw, int16_t *Vs_raw) { + if (!ina226_conv_ready(dev)) + return -1; + + if (I_raw) + *I_raw = (int16_t)ina226_read_reg(dev, INA226_REG_I); + if (V_raw) + *V_raw = (int16_t)ina226_read_reg(dev, INA226_REG_VB); + if (Vs_raw) + *Vs_raw = (int16_t)ina226_read_reg(dev, INA226_REG_VS); + + return 0; +} + +int ina226_read_scaled(struct ina226 *dev, int16_t *I_mA, int16_t *V_mV, int16_t *Vs_uV) { + if (!ina226_conv_ready(dev)) + return -1; + + if (I_mA) + *I_mA = ((int16_t)ina226_read_reg(dev, INA226_REG_I))*dev->i_lsb_uA/1000; + if (V_mV) + *V_mV = ((int16_t)ina226_read_reg(dev, INA226_REG_VB))*INA226_VB_LSB_uV/1000; + if (Vs_uV) + *Vs_uV = ((int16_t)ina226_read_reg(dev, INA226_REG_VS))*INA226_VS_LSB_nV/1000; + + return 0; +} + +bool ina226_conv_ready(struct ina226 *dev) { + /* We need a bit of logic here to track state since this flag auto-resets not only on conversion trigger but also on + * flag read. */ + if (!dev->conv_ready && (ina226_read_reg(dev, INA226_REG_MASK_EN) & INA226_MASK_EN_CVRF)) + dev->conv_ready = true; + return dev->conv_ready; +} diff --git a/fw/ina226.h b/fw/ina226.h new file mode 100644 index 0000000..ffb9f54 --- /dev/null +++ b/fw/ina226.h @@ -0,0 +1,108 @@ +#ifndef __INA226_H__ +#define __INA226_H__ + +#include <stdint.h> +#include <stdbool.h> +#include <limits.h> +#include "i2c.h" + +/* Fixed values from datasheet */ +#define INA226_VB_LSB_uV 1250 +#define INA226_VS_LSB_nV 2500 + +enum ina226_reg { + INA226_REG_CONFIG = 0x00, + INA226_REG_VS = 0x01, + INA226_REG_VB = 0x02, + INA226_REG_P = 0x03, + INA226_REG_I = 0x04, + INA226_REG_CAL = 0x05, + INA226_REG_MASK_EN = 0x06, + INA226_REG_ALERT = 0x07, + INA226_REG_MFGID = 0xfe, + INA226_REG_DIEID = 0xff +}; + +enum ina226_config { + INA226_CONFIG_RST = 1<<15, + + INA226_CONFIG_AVG_Pos = 9, + INA226_CONFIG_AVG_Msk = 3<<9, + INA226_CONFIG_AVG_1 = 0<<9, + INA226_CONFIG_AVG_4 = 1<<9, + INA226_CONFIG_AVG_16 = 2<<9, + INA226_CONFIG_AVG_64 = 3<<9, + INA226_CONFIG_AVG_128 = 4<<9, + INA226_CONFIG_AVG_256 = 5<<9, + INA226_CONFIG_AVG_512 = 6<<9, + INA226_CONFIG_AVG_1024 = 7<<9, + + INA226_CONFIG_VBUSCT_Pos = 6, + INA226_CONFIG_VBUSCT_Msk = 7<<6, + INA226_CONFIG_VBUSCT_140u = 0<<6, + INA226_CONFIG_VBUSCT_204u = 1<<6, + INA226_CONFIG_VBUSCT_332u = 2<<6, + INA226_CONFIG_VBUSCT_588u = 3<<6, + INA226_CONFIG_VBUSCT_1m1 = 4<<6, + INA226_CONFIG_VBUSCT_2m116 = 5<<6, + INA226_CONFIG_VBUSCT_4m156 = 6<<6, + INA226_CONFIG_VBUSCT_8m244 = 7<<6, + + INA226_CONFIG_VSHCT_Pos = 3, + INA226_CONFIG_VSHCT_Msk = 7<<3, + INA226_CONFIG_VSHCT_140u = 0<<3, + INA226_CONFIG_VSHCT_204u = 1<<3, + INA226_CONFIG_VSHCT_332u = 2<<3, + INA226_CONFIG_VSHCT_588u = 3<<3, + INA226_CONFIG_VSHCT_1m1 = 4<<3, + INA226_CONFIG_VSHCT_2m116 = 5<<3, + INA226_CONFIG_VSHCT_4m156 = 6<<3, + INA226_CONFIG_VSHCT_8m244 = 7<<3, + + INA226_CONFIG_MODE_Pos = 0, + INA226_CONFIG_MODE_Msk = 7, + INA226_CONFIG_MODE_POWERDOWN = 0, + + INA226_CONFIG_MODE_SHUNT = 1, + + INA226_CONFIG_MODE_BUS = 2, + + INA226_CONFIG_MODE_TRIG = 0, + INA226_CONFIG_MODE_CONT = 4 +}; + +enum ina226_mask_en { + INA226_MASK_EN_SOL = 1<<15, + INA226_MASK_EN_SUL = 1<<14, + INA226_MASK_EN_BOL = 1<<13, + INA226_MASK_EN_BUL = 1<<12, + INA226_MASK_EN_POL = 1<<11, + INA226_MASK_EN_CNVR = 1<<10, + INA226_MASK_EN_AFF = 1<<4, + INA226_MASK_EN_CVRF = 1<<3, + INA226_MASK_EN_OVF = 1<<2, + INA226_MASK_EN_APOL = 1<<1, + INA226_MASK_EN_LEN = 1<<0 +}; + +struct ina226 { + I2C_TypeDef *i2c_periph; + uint8_t i2c_addr; + uint16_t rs_uOhm; + uint16_t conv_config; + uint16_t i_lsb_uA; + bool conv_ready:1; +}; + +/* High-level API */ +void ina226_init(struct ina226 *dev, I2C_TypeDef *i2c_periph, uint8_t i2c_addr, uint16_t rs_uOhm, uint16_t conv_config); +void ina226_trigger(struct ina226 *dev, int mode); +bool ina226_conv_ready(struct ina226 *dev); +int ina226_read_raw(struct ina226 *dev, int16_t *I_raw, int16_t *V_raw, int16_t *Vs_raw); +int ina226_read_scaled(struct ina226 *dev, int16_t *I_mA, int16_t *V_mV, int16_t *Vs_uV); + +/* Low-level API */ +void ina226_write_reg(struct ina226 *dev, uint8_t reg, uint16_t val); +uint16_t ina226_read_reg(struct ina226 *dev, uint8_t reg); + +#endif /* __INA226_H__ */ diff --git a/fw/lcd1602.c b/fw/lcd1602.c new file mode 100644 index 0000000..6d71638 --- /dev/null +++ b/fw/lcd1602.c @@ -0,0 +1,187 @@ +/*
+ This is free and unencumbered software released into the public domain.
+ ( https://github.com/KonstantinDM )
+
+ Anyone is free to copy, modify, publish, use, compile, sell, or
+ distribute this software, either in source code form or as a compiled
+ binary, for any purpose, commercial or non-commercial, and by any
+ means.
+
+ In jurisdictions that recognize copyright laws, the author or authors
+ of this software dedicate any and all copyright interest in the
+ software to the public domain. We make this dedication for the benefit
+ of the public at large and to the detriment of our heirs and
+ successors. We intend this dedication to be an overt act of
+ relinquishment in perpetuity of all present and future rights to this
+ software under copyright law.
+
+ 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 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.
+
+ For more information, please refer to <http://unlicense.org>
+ */
+
+#include "global.h"
+#include "i2c.h"
+#include "lcd1602.h"
+
+static void write_byte(uint8_t in_u8Byte); // Отпвить байт на шину
+static void send_half_byte(uint8_t in_u8Byte); // Отправить пол байта
+static void send_command(uint8_t in_u8Byte); // Отправить байт команду
+static void delay_micro(uint32_t in_u8micros);
+
+static uint8_t lcd_gpio = 0;
+
+/*
+ Инициализация дисплея, обязательнаяпроцедура
+ на входе: *
+ на выходе: *
+*/
+void lcd1602_init()
+{
+ // Инициализация экрана обязательна
+ delay_micro(150000);
+ send_half_byte(LCD_INITIALIZATION);
+ delay_micro(40000);
+ send_half_byte(LCD_INITIALIZATION);
+ delay_micro(1000000);
+ send_half_byte(LCD_INITIALIZATION);
+ delay_micro(10000);
+ send_half_byte(LCD_SET_CURSOR_TO_START);
+
+ // Найстрока дисплея
+ send_command(LCD_SET_INTERFACE_LINES_FONT | LCD_4BIT_INTERFACE | LCD_TWO_LINE | LCD_5x8_FONT);
+ send_command(LCD_SET_CURSOR_AND_POWE_MODE | LCD_DISPLAY_ON | LCD_CURSOR_OFF | LCD_CURSOR_BLINK_OFF);
+ send_command(LCD_SET_SHIFT_AND_CHAR_DIRECTION | LCD_CHAR_DIRECTION_LEFT_RIGHT | LCD_SHIFT_DISABLE);
+
+ // Очистить экран
+ lcd_clear();
+
+ // Включить подсветку и режим записи
+ lcd_gpio |= LCD_MODE_LED;
+ lcd_gpio &= ~LCD_MODE_WRITE;
+};
+
+/*
+ Отправить строку на экран с указанием позиции
+ на входе: in_u8X - позиция символа в строке
+ in_u8Y - номер строки
+ in_cChar - символ для установки
+ на выходе: *
+*/
+void lcd_write_str(uint8_t in_u8X, uint8_t in_u8Y, char* in_cChar)
+{
+ lcd_set_pos(in_u8X, in_u8Y);
+ lcd_send_str(in_cChar);
+};
+
+/*
+ Установка курсора
+ на входе: in_u8X - позиция символа в строке
+ in_u8Y - номер строки
+ на выходе: *
+*/
+void lcd_set_pos(uint8_t in_u8X, uint8_t in_u8Y)
+{
+ switch (in_u8Y) {
+ case 0:
+ send_command(in_u8X | LCD_SET_DDRAM_TO_ADDRESS);
+ break;
+ case 1:
+ send_command((LCD_2_LINE_OFFSET + in_u8X) | LCD_SET_DDRAM_TO_ADDRESS);
+ break;
+ }
+};
+
+/*
+ Отправка строки на экран
+ на входе: in_cChar - указатель на строку
+ на выходе: *
+*/
+void lcd_send_str(char* in_pszChar)
+{
+ char* l_pszChar = in_pszChar;
+ while ((l_pszChar)[0])
+ lcd_send_char((l_pszChar++)[0]);
+};
+
+/*
+ Отправка символа на экран
+ на входе: in_cChar - символ
+ на выходе: *
+*/
+void lcd_send_char(char in_cChar)
+{
+ lcd_gpio |= LCD_MODE_DATA;
+ send_half_byte(in_cChar >> 4);
+ send_half_byte(in_cChar);
+};
+
+/*
+ Очистить экран
+ на входе: *
+ на выходе: *
+*/
+void lcd_clear()
+{
+ send_command(LCD_SET_CLEAR);
+ delay_micro(35300);
+};
+
+/*
+ Отправка байта на шину
+ на входе: in_u8Byte - байт с командой
+ на выходе: *
+*/
+void write_byte(uint8_t in_u8Byte)
+{
+ uint8_t buf[1] = { lcd_gpio | in_u8Byte };
+
+ i2c_transmit(LCD_I2C_PERIPH, buf, 1, LCD_I2C_ADDR, I2C_GENSTOP_YES);
+ delay_micro(39);
+};
+
+void i2c_transmit_one(const uint8_t b) {
+ LCD_I2C_PERIPH->CR2 = LCD_I2C_ADDR | I2C_CR2_START | I2C_CR2_AUTOEND | (1 << I2C_CR2_NBYTES_Pos);
+}
+
+/*
+ Отправка половины байта экрану
+ на входе: in_u8Byte - байт с командой
+ на выходе: *
+*/
+void send_half_byte(uint8_t in_u8Byte)
+{
+ write_byte(LCD_MODE_E_SET | (in_u8Byte << 4));
+ write_byte(LCD_MODE_E_RESET);
+};
+
+/*
+ Отправка команды дисплею
+ на входе: in_u8Byte - байт с командой
+ на выходе: *
+*/
+void send_command(uint8_t in_u8Byte)
+{
+ lcd_gpio &= ~LCD_MODE_DATA;
+ send_half_byte(in_u8Byte >> 4);
+ send_half_byte(in_u8Byte);
+};
+
+/*
+ Отправка половины байта экрану
+ на входе: in_u8Byte - байт с командой
+ на выходе: *
+*/
+void delay_micro(uint32_t in_u8micros)
+{
+ /* FIXME */
+ in_u8micros *= (SystemCoreClock / 1000000) / 9;
+ while (in_u8micros--)
+ ;
+};
diff --git a/fw/lcd1602.h b/fw/lcd1602.h new file mode 100644 index 0000000..4cb2758 --- /dev/null +++ b/fw/lcd1602.h @@ -0,0 +1,98 @@ +/*
+ This is free and unencumbered software released into the public domain.
+ ( https://github.com/KonstantinDM )
+
+ Anyone is free to copy, modify, publish, use, compile, sell, or
+ distribute this software, either in source code form or as a compiled
+ binary, for any purpose, commercial or non-commercial, and by any
+ means.
+
+ In jurisdictions that recognize copyright laws, the author or authors
+ of this software dedicate any and all copyright interest in the
+ software to the public domain. We make this dedication for the benefit
+ of the public at large and to the detriment of our heirs and
+ successors. We intend this dedication to be an overt act of
+ relinquishment in perpetuity of all present and future rights to this
+ software under copyright law.
+
+ 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 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.
+
+ For more information, please refer to <http://unlicense.org>
+ */
+
+#ifndef _C_LCD1602_H_INCLUDED_
+#define _C_LCD1602_H_INCLUDED_
+
+#define LCD_I2C_PERIPH I2C1
+#define LCD_I2C_ADDR 0x4e
+
+/* 16 spaces you can concatenate to printf formats to make sure the entire LCD line is always cleared */
+#define LCD_FILL " "" "" "" "
+
+void lcd1602_init(); // Инициализация дисплея
+void lcd_write_str(uint8_t in_u8X, uint8_t in_u8Y, char* in_cChar); // Отправить строку на экран с указанием позиции
+void lcd_send_char(char in_cChar); // Отправить символ на экран
+void lcd_send_str(char* in_cChar); // Отправить строку на экран
+void lcd_set_pos(uint8_t in_u8X, uint8_t in_u8Y); // Установить позицию курсора
+void lcd_clear(); // Очистить экран
+
+/*
+ |P7|P6|P5|P4|P3|P2|P1|P0|
+ |B7|B6|B5|B4|LED|E|RW|RS|
+*/
+
+#define LCD_INITIALIZATION 0x03 // Инициализационный байт дисплея
+
+#define LCD_MODE_COMMAND 0x00 // Флаг команды
+#define LCD_MODE_DATA 0x01 // Флаг данных
+#define LCD_MODE_LED 0x08 // флаг работы подсветки
+#define LCD_MODE_WRITE 0x02 // Флаг записи
+#define LCD_MODE_E_SET 0x04 // Флаг установки регистра Е
+#define LCD_MODE_E_RESET 0xFB // Флаг сброса регистра Е
+
+#define LCD_2_LINE_OFFSET 0x40 // Адрес второй строки дисплея
+
+#define LCD_SET_CLEAR 0x01 // (1.53ms) Очистка дисплея с установкой курсора в начало первой строки
+#define LCD_SET_CURSOR_TO_START 0x02 // (1.53ms) Установка курсора в начало первой строки
+
+#define LCD_SET_SHIFT_AND_CHAR_DIRECTION 0x04 // (39mks) Установка направления вывода символов, разрешение сдвига экрана
+#define LCD_CHAR_DIRECTION_LEFT_RIGHT 0x02 // Вывод символов справа-налево, декремент адресного указателя DDRAM/CGRAM памяти
+#define LCD_CHAR_DIRECTION_RIGHT_LEFT 0x00 // Вывод символов слева-направо, инкремент адресного указателя DDRAM/CGRAM памяти
+#define LCD_SHIFT_DISABLE 0x00 // Запрет сдвига экрана при выводе символов
+#define LCD_SHIFT_ENABLE 0x01 // Разрешение сдвига экрана при выводе символов
+
+#define LCD_SET_CURSOR_AND_POWE_MODE 0x08 // (39mks) Управление режимом питания дисплея и отображением курсора
+#define LCD_DISPLAY_OFF 0x00 // Выключить экран дисплея, сегменты погашены, содержимое внутренней памяти сохраняется
+#define LCD_DISPLAY_ON 0x04 // Включить экран дисплея, нормальный режим работы
+#define LCD_CURSOR_OFF 0x00 // Отключить отображение курсора
+#define LCD_CURSOR_ON 0x02 // Включить отображение курсора
+#define LCD_CURSOR_BLINK_OFF 0x00 // Отключить функцию мигания курсора
+#define LCD_CURSOR_BLINK_ON 0x01 // Включить функцию мигания курсора
+
+#define LCD_SET_CURSOR_AND_DISPLAY_SHIFT 0x10 // (39mks) Команда сдвига курсора и экрана
+#define LCD_CURSOR_SHIFT 0x00 // Выбрать курсор для сдвига
+#define LCD_DISPLAY_AND_CURSOR_SHIFT 0x08 // Выбрать экран (вместе с курсором) для сдвига
+#define LCD_LEFT_SHIFT 0x00 // Сдвиг влево (только курсор или весь экран, зависит от бита S/C)
+#define LCD_RIGHT_SHIFT 0x04 // Сдвиг вправо (только курсор или весь экран, зависит от бита S/C)
+
+#define LCD_SET_INTERFACE_LINES_FONT 0x20 // (39mks) Настройка интерфейса ввода/вывода данных, количества строк для вывода символов, размера шрифта
+#define LCD_4BIT_INTERFACE 0x00 // Сдвиг вправо (только курсор или весь экран, зависит от бита S/C)
+#define LCD_8BIT_INTERFACE 0x10 // 8-битный интерфейс ввода/вывода данных
+#define LCD_ONE_LINE 0x00 // Использовать одну строку для вывода символов
+#define LCD_TWO_LINE 0x08 // Задействовать 2 строки для вывода символов
+#define LCD_5x8_FONT 0x00 // Размер шрифта 5×8 пикселей
+#define LCD_5x11_FONT 0x04 // Размер шрифта 5×11 пикселей
+
+#define LCD_SET_CGRAM_TO_ADDRESS 0x40 // (39mks) Запись адреса CGRAM памяти в адресный указатель
+#define LCD_CGRAM_TO_ADDRESS_MASK 0x3F // Маска байта данных
+
+#define LCD_SET_DDRAM_TO_ADDRESS 0x80 // (39mks) Запись адреса DDRAM памяти в адресный указатель
+#define LCD_DDRAM_TO_ADDRESS_MASK 0x7F // Маска байта данных
+
+#endif // _C_LCD1602_H_INCLUDED_
diff --git a/fw/mac.c b/fw/mac.c new file mode 100644 index 0000000..b2fb48a --- /dev/null +++ b/fw/mac.c @@ -0,0 +1,3 @@ +#include "mac.h" + +uint32_t device_mac = MAC_ADDR; diff --git a/fw/mac.h b/fw/mac.h new file mode 100644 index 0000000..26aaff6 --- /dev/null +++ b/fw/mac.h @@ -0,0 +1,22 @@ +#ifndef __MAC_H__ +#define __MAC_H__ + +#include <unistd.h> + +/* Device MAC address. + * + * 32 bits might seem a little short for a device MAC, but at 20 bus nodes the probablility of a collision is about 1 in + * 10 million. Check for yourself using the python code below. + * + * #!/usr/bin/env python3 + * from operator import mul + * from functools import reduce + * m = 32 + * n = 20 + * print(reduce(mul, [2**m-i for i in range(n)]) / ((2**m)**n)) + * # -> 0.9999999557621786 + */ + +extern uint32_t device_mac; + +#endif /* __MAC_H__ */ diff --git a/fw/main.c b/fw/main.c new file mode 100644 index 0000000..c60dff0 --- /dev/null +++ b/fw/main.c @@ -0,0 +1,502 @@ +/* 8seg LED display driver firmware + * Copyright (C) 2018 Sebastian Götte <code@jaseg.net> + * + * 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 3 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, see <http://www.gnu.org/licenses/>. + */ + + +#include "global.h" +#include "serial.h" +#include "i2c.h" +#include "lcd1602.h" + +#include "mini-printf.h" + +/* Part number: STM32F030F4C6 */ + +volatile unsigned int comm_led_ctr, err_led_ctr; +volatile unsigned int sys_time_tick = 0; +volatile unsigned int sys_time_ms; +volatile unsigned int sys_time_s; +volatile unsigned int sys_flag_1Hz; +unsigned int frame_duration_us; +volatile uint8_t global_brightness; /* FIXME implement sending */ +volatile bool display_update_flag; +volatile bool adc_trigger_flag = 0; +volatile bool backchannel_trigger_flag = 0; + +void run_menu(void); +void update_display(void); +void calc_next_alarm(void); + +uint8_t random() { + static uint8_t x, a, b, c; + x++; //x is incremented every round and is not affected by any other variable + a = (a ^ c ^ x); //note the mix of addition and XOR + b = (b + a); //And the use of very few instructions + c = ((c + ((b >> 1) ^ a))); // the AES S-Box Operation ensures an even distributon of entropy + return c; +} + +volatile int input_hold_total[5] = {0}; +volatile int input_triggered = 0; +volatile int input_state = 0; + +void rtc_adjust(int field, int adj) { + RTC->ISR = RTC_ISR_INIT; + while (!(RTC->ISR & RTC_ISR_INITF)) + ; + + int offx = field*8; + int fmax = field == 2 ? 24 : 60; + + int tr = RTC->TR; + int fval = (tr >> offx) & 0xff; + + fval = (fval&0xf) + 10*(fval>>4); + + if (field == 0) { + /* seconds field special handling: set seconds to 0 when pressing down, ignore up */ + if (adj < 0) + fval = 0; + } else { + fval += adj; + } + + if (fval < 0) + fval = fmax-1; + if (fval >= fmax) + fval = 0; + + fval = ((fval/10)<<4) | (fval % 10); + + RTC->TR = (tr & ~(0xff<<offx)) | (fval << offx); + RTC->ISR = 0; + while (!(RTC->ISR & RTC_ISR_RSF)) + ; +} + +int main(void) { + /* Startup code */ + RCC->CR |= RCC_CR_HSEON; + while (!(RCC->CR&RCC_CR_HSERDY)); + RCC->CFGR &= ~RCC_CFGR_PLLMUL_Msk & ~RCC_CFGR_SW_Msk & ~RCC_CFGR_PPRE_Msk & ~RCC_CFGR_HPRE_Msk; + RCC->CFGR |= ((6-2)<<RCC_CFGR_PLLMUL_Pos) | RCC_CFGR_PLLSRC_HSE_PREDIV; /* PLL x6 -> 48.0MHz */ + RCC->CR |= RCC_CR_PLLON; + while (!(RCC->CR&RCC_CR_PLLRDY)); + RCC->CFGR |= (2<<RCC_CFGR_SW_Pos); + RCC->AHBENR |= RCC_AHBENR_DMAEN | RCC_AHBENR_GPIOAEN | RCC_AHBENR_GPIOBEN | RCC_AHBENR_FLITFEN; + RCC->APB1ENR |= RCC_APB1ENR_TIM3EN | RCC_APB1ENR_PWREN | RCC_APB1ENR_I2C1EN; + RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN | RCC_APB2ENR_ADCEN| RCC_APB2ENR_DBGMCUEN | RCC_APB2ENR_USART1EN | RCC_APB2ENR_SPI1EN | RCC_APB2ENR_TIM1EN; + RCC->CFGR3 |= RCC_CFGR3_I2C1SW; /* Route 48MHz system clock to I2C1 */ + + PWR->CR |= PWR_CR_DBP; + RCC->BDCR = RCC_BDCR_BDRST; + RCC->BDCR = 0; + RCC->BDCR = RCC_BDCR_RTCEN | (3<<RCC_BDCR_RTCSEL_Pos); + + RTC->WPR = 0xca; + RTC->WPR = 0x53; + RTC->ISR = RTC_ISR_INIT; + while (!(RTC->ISR & RTC_ISR_INITF)) + ; + RTC->PRER = (99 << RTC_PRER_PREDIV_A_Pos) | (2499 << RTC_PRER_PREDIV_S_Pos); + RTC->SSR = 0; + RTC->TR = 0; + RTC->DR = 0; + RTC->TSTR = 0; + RTC->TSDR = 0; + RTC->CR |= RTC_CR_ALRAIE; + EXTI->IMR |= 1<<17; + EXTI->RTSR |= 1<<17; + RTC->ISR = 0; + while (!(RTC->ISR & RTC_ISR_RSF)) + ; + + SystemCoreClockUpdate(); + SysTick_Config(SystemCoreClock/(1000/TICK_MS)); /* 10ms interval */ + NVIC_EnableIRQ(SysTick_IRQn); + NVIC_SetPriority(SysTick_IRQn, 3<<5); + + /* GPIO setup + * + * Note: since we have quite a bunch of pin constraints we can't actually use complementary outputs for the + * complementary MOSFET driver control signals (CTRL_A & CTRL_B). Instead, we use two totally separate output + * channels (1 & 4) and emulate the dead-time generator in software. + */ + GPIOA->MODER |= + (2<<GPIO_MODER_MODER6_Pos) /* PA6 - servo / TIM3_CH1 */ + | (2<<GPIO_MODER_MODER9_Pos) /* PA9 - SCL */ + | (2<<GPIO_MODER_MODER10_Pos);/* PA10 - SDA */ + + GPIOA->AFR[0] = + (1<<GPIO_AFRH_AFSEL9_Pos); /* PA6 */ + GPIOA->AFR[1] = + (4<<GPIO_AFRH_AFSEL9_Pos) /* PA9 */ + | (4<<GPIO_AFRH_AFSEL10_Pos);/* PA10 */ + + for (int i=0; i<5; i++) + GPIOA->PUPDR |= 1<<(2*i); + + /* I2C for LCD, temp sensor, current sensor */ + i2c_config_filters(I2C1, I2C_AF_ENABLE, 0); + i2c_config_timing(I2C1, 0x50330309); /* Magic value for 400kHz I2C @ 48MHz CLK. From the datasheet. The other option + is to have this fall out of STMCubeMX. I love downloading 120MB of software + to download another 100MB of software, only this time over unsecured HTTP, + to generate 3.5 bytes of configuration values using a Java(TM) GUI. */ + i2c_enable(I2C1); + lcd1602_init(); + + lcd_write_str(0, 0, "timer initialized \xbc" LCD_FILL); + lcd_write_str(0, 1, LCD_FILL); + + /* servo output */ + TIM1->CR1 = TIM_CR1_CEN; + TIM1->PSC = 48-1; /* 1us ticks */ + TIM1->ARR = 1000-1; /* 1ms interval */ + TIM1->EGR = TIM_EGR_UG; + TIM1->CCMR1 = (6<<TIM_CCMR1_OC1M_Pos); + TIM1->CCER = TIM_CCER_CC1E; + TIM1->DIER = TIM_DIER_UIE; + + TIM3->CR1 = TIM_CR1_CEN; + TIM3->PSC = 48-1; /* 1us ticks */ + TIM3->ARR = 20000-1; /* 20ms interval */ + TIM3->EGR = TIM_EGR_UG; + + NVIC_EnableIRQ(TIM1_BRK_UP_TRG_COM_IRQn); + NVIC_EnableIRQ(RTC_IRQn); + calc_next_alarm(); + + uint32_t last_update_ms = 0; + const int display_update_ivl_ms = 50; + while(23) { + int delta = sys_time_ms - last_update_ms; + if (delta < 0) + delta += 1000; + if (delta > display_update_ivl_ms) + update_display(); + } +} + +enum { + MENU_DEFAULT, + MENU_SET_TIME, + MENU_SET_ALARM, +} menu_state; + +int menu_adjustment_done = 0; +int sel_field_idx = 0; +int menu_alarm = 0; + +enum { + INPUT_LEFT, + INPUT_DOWN, + INPUT_UP, + INPUT_RIGHT, + INPUT_MENU +}; + +enum { + ALR_TON, + ALR_TOFF, + NUM_ALARMS +}; + +int alarms[NUM_ALARMS] = { + 9<<16 | 0<<8 | 0, + 21<<16 | 0<<8 | 0, +}; +const char *alarm_names[NUM_ALARMS] = {" ON", "OFF"}; +int next_alarm = -1; + +void RTC_IRQHandler() { + RTC->ISR &= ~RTC_ISR_ALRAF; + EXTI->PR = 1<<17; + calc_next_alarm(); + /* TODO FIXME handle alarm */ +} + +void adj_alarm(int alarm, int sel, int adj) { + int fields[3] = { alarms[alarm]>>16, (alarms[alarm]>>8) & 0xff, alarms[alarm] & 0xff }; + int max[3] = { 24, 60, 60 }; + sel = 2-sel; + + fields[sel] += adj; + if (fields[sel] < 0) + fields[sel] += max[sel]; + if (fields[sel] >= max[sel]) + fields[sel] -= max[sel]; + + alarms[alarm] = (fields[0]<<16) | (fields[1]<<8) | fields[2]; +} + +void calc_next_alarm() { + int tr = RTC->TR; + int h = ((tr>>RTC_TR_HT_Pos)&3)*10 + ((tr>>RTC_TR_HU_Pos)&0xf), + m = ((tr>>RTC_TR_MNT_Pos)&7)*10 + ((tr>>RTC_TR_MNU_Pos)&0xf), + s = ((tr>>RTC_TR_ST_Pos)&7)*10 + ((tr>>RTC_TR_SU_Pos)&0xf); + int tr_al_fmt = h<<16 | m<<8 | s; + + int min_alr = 0x7fffffff; + int min_idx = -1; + for (int i=0; i<NUM_ALARMS; i++) { + if (alarms[i] > tr_al_fmt && alarms[i] < min_alr) { + min_alr = alarms[i]; + min_idx = i; + } + } + + if (min_idx == -1) { /* handle rollover */ + for (int i=0; i<NUM_ALARMS; i++) { + if (alarms[i] < min_alr) { + min_alr = alarms[i]; + min_idx = i; + } + } + } + + next_alarm = min_idx; + RTC->CR &= ~RTC_CR_ALRAE; + while (!(RTC->ISR & RTC_ISR_ALRAWF)) + ; + h = min_alr>>16, m = (min_alr>>8)&0xff, s = min_alr & 0xff; + RTC->ALRMAR = RTC_ALRMAR_MSK4 + | (h/10 << RTC_ALRMAR_HT_Pos) | (h%10 << RTC_ALRMAR_HU_Pos) + | (m/10 << RTC_ALRMAR_MNT_Pos) | (m%10 << RTC_ALRMAR_MNU_Pos) + | (s/10 << RTC_ALRMAR_ST_Pos) | (s%10 << RTC_ALRMAR_SU_Pos); + RTC->ISR &= ~RTC_ISR_ALRAF; + RTC->CR |= RTC_CR_ALRAE; +} + +void update_display() { + char buf[17]; + bool blink_flag = sys_time_ms < 300; + int tr = RTC->TR; + + switch (menu_state) { + case MENU_DEFAULT: + mini_snprintf(buf, sizeof(buf), "%d%d:%d%d:%d%d" LCD_FILL, + (tr>>RTC_TR_HT_Pos)&3, (tr>>RTC_TR_HU_Pos)&0xf, + (tr>>RTC_TR_MNT_Pos)&7, (tr>>RTC_TR_MNU_Pos)&0xf, + (tr>>RTC_TR_ST_Pos)&7, (tr>>RTC_TR_SU_Pos)&0xf); + lcd_write_str(0, 0, buf); + if (next_alarm < 0) { + mini_snprintf(buf, sizeof(buf), LCD_FILL); + } else { + int next = alarms[next_alarm]; + int h = next>>16, m = (next>>8) & 0xff, s = next & 0xff; + mini_snprintf(buf, sizeof(buf), "%s AT %02d:%02d:%02d" LCD_FILL, alarm_names[next_alarm], h, m, s); + } + lcd_write_str(0, 1, buf); + break; + + case MENU_SET_TIME: + mini_snprintf(buf, sizeof(buf), "%d%d:%d%d:%d%d" LCD_FILL, + (tr>>RTC_TR_HT_Pos)&3, (tr>>RTC_TR_HU_Pos)&0xf, + (tr>>RTC_TR_MNT_Pos)&7, (tr>>RTC_TR_MNU_Pos)&0xf, + (tr>>RTC_TR_ST_Pos)&7, (tr>>RTC_TR_SU_Pos)&0xf); + if (sel_field_idx == 0 && blink_flag) + buf[6] = buf[7] = ' '; + if (sel_field_idx == 1 && blink_flag) + buf[3] = buf[4] = ' '; + if (sel_field_idx == 2 && blink_flag) + buf[0] = buf[1] = ' '; + lcd_write_str(0, 0, buf); + mini_snprintf(buf, sizeof(buf), "SET TIME" LCD_FILL); + lcd_write_str(0, 1, buf); + break; + + case MENU_SET_ALARM: + mini_snprintf(buf, sizeof(buf), "%02d:%02d:%02d" LCD_FILL, + alarms[menu_alarm]>>16, (alarms[menu_alarm]>>8) & 0xff, alarms[menu_alarm] & 0xff); + if (sel_field_idx == 0 && blink_flag) + buf[6] = buf[7] = ' '; + if (sel_field_idx == 1 && blink_flag) + buf[3] = buf[4] = ' '; + if (sel_field_idx == 2 && blink_flag) + buf[0] = buf[1] = ' '; + lcd_write_str(0, 0, buf); + mini_snprintf(buf, sizeof(buf), "SET %s" LCD_FILL, alarm_names[menu_alarm]); + lcd_write_str(0, 1, buf); + break; + } +} + +void run_menu() { + + const int enter_program_mode_ms = 1000; + + int btn = input_triggered; + input_triggered = 0; + + switch (menu_state) { + case MENU_DEFAULT: + if (input_state == (1<<INPUT_MENU) && input_hold_total[INPUT_MENU] >= enter_program_mode_ms) { + menu_state = MENU_SET_TIME; + sel_field_idx = 0; + menu_adjustment_done = 0; + } + break; + + case MENU_SET_TIME: + if (btn & (1<<INPUT_MENU)) { + if (menu_adjustment_done) { + menu_state = MENU_DEFAULT; + calc_next_alarm(); + } else { + menu_state = MENU_SET_ALARM; + sel_field_idx = 2; + menu_alarm = 0; + } + break; + } + + if (btn & (1<<INPUT_LEFT)) { + menu_adjustment_done = 1; + sel_field_idx++; + if (sel_field_idx > 2) + sel_field_idx = 0; + } + if (btn & (1<<INPUT_RIGHT)) { + menu_adjustment_done = 1; + sel_field_idx--; + if (sel_field_idx < 0) + sel_field_idx = 2; + } + + if (btn & (1<<INPUT_UP)) { + menu_adjustment_done = 1; + rtc_adjust(sel_field_idx, 1); + } + if (btn & (1<<INPUT_DOWN)) { + menu_adjustment_done = 1; + rtc_adjust(sel_field_idx, -1); + } + break; + + case MENU_SET_ALARM: + if (btn & (1<<INPUT_MENU)) { + if (menu_adjustment_done) { + menu_state = MENU_DEFAULT; + calc_next_alarm(); + } else { + sel_field_idx = 2; + menu_alarm++; + if (menu_alarm == NUM_ALARMS) + menu_state = MENU_DEFAULT; + } + break; + } + + if (btn & (1<<INPUT_LEFT)) { + menu_adjustment_done = 1; + sel_field_idx++; + if (sel_field_idx > 2) + sel_field_idx = 0; + } + if (btn & (1<<INPUT_RIGHT)) { + menu_adjustment_done = 1; + sel_field_idx--; + if (sel_field_idx < 0) + sel_field_idx = 2; + } + + if (btn & (1<<INPUT_UP)) { + menu_adjustment_done = 1; + adj_alarm(menu_alarm, sel_field_idx, 1); + } + if (btn & (1<<INPUT_DOWN)) { + menu_adjustment_done = 1; + adj_alarm(menu_alarm, sel_field_idx, -1); + } + break; + } +} + +void TIM1_BRK_UP_TRG_COM_IRQHandler() { /* every 1ms */ + TIM1->SR &= ~TIM_SR_UIF; + int inputs = (~GPIOA->IDR) & 0x1f; + input_state = inputs; + static int input_debounce[5] = {0}; + static int input_hold[5] = {0}; + + const int input_debounce_time_ms = 20; + const int input_hold_retrigger_backoff_ms = 1000; + const int input_hold_retrigger_ms = 120; + + for (int i=0; i<5; i++) { + int bit = inputs&1; + inputs >>= 1; + + if (bit) { + if (!input_debounce[i]) { + input_triggered |= 1<<i; + } + input_debounce[i] = input_debounce_time_ms; + + input_hold_total[i]++; + if (i == INPUT_UP || i == INPUT_DOWN) { + /* retrigger for UP and DOWN buttons */ + if (input_hold_total[i] > input_hold_retrigger_backoff_ms) { + input_hold[i]++; + if (input_hold[i] == input_hold_retrigger_ms) { + input_hold[i] = 0; + input_triggered |= 1<<i; + } + } + } + } else { + if (input_debounce[i]) + input_debounce[i]--; + input_hold[i] = 0; + input_hold_total[i] = 0; + } + } + + run_menu(); +} + +void NMI_Handler(void) { +} + +void HardFault_Handler(void) __attribute__((naked)); +void HardFault_Handler() { + asm volatile ("bkpt"); +} + +void SVC_Handler(void) { +} + + +void PendSV_Handler(void) { +} + +void SysTick_Handler(void) { + sys_time_tick++; + sys_time_ms += TICK_MS; + if (sys_time_ms++ >= 1000) { + sys_time_ms = 0; + sys_time_s++; + sys_flag_1Hz = 1; + } +} + +void _init(void) { +} + +void BusFault_Handler(void) __attribute__((naked)); +void BusFault_Handler() { + asm volatile ("bkpt"); +} diff --git a/fw/mcp9801.c b/fw/mcp9801.c new file mode 100644 index 0000000..76aac1e --- /dev/null +++ b/fw/mcp9801.c @@ -0,0 +1,42 @@ +/* 8seg LED display driver firmware + * Copyright (C) 2018 Sebastian Götte <code@jaseg.net> + * + * 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 3 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, see <http://www.gnu.org/licenses/>. + */ + +#include "global.h" +#include "i2c.h" +#include "mcp9801.h" + +void mcp9801_init() +{ + uint8_t config = MCP9801_ONESHOT_OFF | MCP9801_RES_12BIT | MCP9801_FAULT_QUEUE_1 | MCP9801_ALERT_LOW | \ + MCP9801_MODE_COMP | MCP9801_SHUTDOWN_OFF; + uint8_t buf[2] = { MCP9801_REG_CONFIG, config }; + i2c_transmit(MCP9801_I2C_PERIPH, buf, sizeof(buf), MCP9801_I2C_ADDR, I2C_GENSTOP_YES); + + /* Address device here */ + uint8_t buf2[1] = { MCP9801_REG_TEMP }; + i2c_transmit(MCP9801_I2C_PERIPH, buf2, sizeof(buf2), MCP9801_I2C_ADDR, I2C_GENSTOP_NO); +} + +int32_t mcp9801_read_mdegC() +{ + uint8_t rx[2]; + i2c_receive(MCP9801_I2C_PERIPH, rx, sizeof(rx), MCP9801_I2C_ADDR); + + /* Fixup endianness, sign-extend */ + int32_t temp = (int16_t)((rx[0]<<8) | rx[1]); + return (temp * 1000) /256; +} diff --git a/fw/mcp9801.h b/fw/mcp9801.h new file mode 100644 index 0000000..6060c98 --- /dev/null +++ b/fw/mcp9801.h @@ -0,0 +1,66 @@ +/* 8seg LED display driver firmware + * Copyright (C) 2018 Sebastian Götte <code@jaseg.net> + * + * 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 3 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, see <http://www.gnu.org/licenses/>. + */ + +#ifndef __MCP9801_H__ +#define __MCP9801_H__ + +#define MCP9801_I2C_ADDR 0x90 +#define MCP9801_I2C_PERIPH I2C1 + +#include <stdint.h> + +enum mcp9801_regmap { + MCP9801_REG_TEMP = 0, + MCP9801_REG_CONFIG = 1, + MCP9801_REG_HYST = 2, + MCP9801_REG_LIMIT = 3 +}; + +enum mcp9801_config { + MCP9801_ONESHOT_ON = 1<<7, + MCP9801_ONESHOT_OFF = 0<<7, + MCP9801_ONESHOT_Msk = 1<<7, + + MCP9801_RES_9BIT = 0<<5, + MCP9801_RES_10BIT = 1<<5, + MCP9801_RES_11BIT = 2<<5, + MCP9801_RES_12BIT = 3<<5, + MCP9801_RES_Msk = 3<<5, + + MCP9801_FAULT_QUEUE_1 = 0<<3, + MCP9801_FAULT_QUEUE_2 = 1<<3, + MCP9801_FAULT_QUEUE_4 = 2<<3, + MCP9801_FAULT_QUEUE_6 = 3<<3, + MCP9801_FAULT_QUEUE_Msk = 3<<3, + + MCP9801_ALERT_HIGH = 1<<2, + MCP9801_ALERT_LOW = 0<<2, + MCP9801_ALERT_Msk = 1<<2, + + MCP9801_MODE_INT = 1<<1, + MCP9801_MODE_COMP = 0<<1, + MCP9801_MODE_Msk = 1<<1, + + MCP9801_SHUTDOWN_ON = 1<<0, + MCP9801_SHUTDOWN_OFF = 0<<0, + MCP9801_SHUTDOWN_Msk = 1<<0, +}; + +void mcp9801_init(void); +int32_t mcp9801_read_mdegC(void); + +#endif /* __MCP9801_H__ */ diff --git a/fw/mini-printf.c b/fw/mini-printf.c new file mode 100644 index 0000000..53cfe99 --- /dev/null +++ b/fw/mini-printf.c @@ -0,0 +1,208 @@ +/* + * The Minimal snprintf() implementation + * + * Copyright (c) 2013,2014 Michal Ludvig <michal@logix.cz> + * 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. + * * Neither the name of the auhor nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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 AUTHOR 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. + * + * ---- + * + * This is a minimal snprintf() implementation optimised + * for embedded systems with a very limited program memory. + * mini_snprintf() doesn't support _all_ the formatting + * the glibc does but on the other hand is a lot smaller. + * Here are some numbers from my STM32 project (.bin file size): + * no snprintf(): 10768 bytes + * mini snprintf(): 11420 bytes (+ 652 bytes) + * glibc snprintf(): 34860 bytes (+24092 bytes) + * Wasting nearly 24kB of memory just for snprintf() on + * a chip with 32kB flash is crazy. Use mini_snprintf() instead. + * + */ + +#include "mini-printf.h" + +static unsigned int +mini_strlen(const char *s) +{ + unsigned int len = 0; + while (s[len] != '\0') len++; + return len; +} + +static unsigned int +mini_itoa(int value, unsigned int radix, unsigned int uppercase, unsigned int unsig, + char *buffer, unsigned int zero_pad) +{ + char *pbuffer = buffer; + int negative = 0; + unsigned int i, len; + + /* No support for unusual radixes. */ + if (radix > 16) + return 0; + + if (value < 0 && !unsig) { + negative = 1; + value = -value; + } + + /* This builds the string back to front ... */ + do { + int digit = value % radix; + *(pbuffer++) = (digit < 10 ? '0' + digit : (uppercase ? 'A' : 'a') + digit - 10); + value /= radix; + } while (value > 0); + + for (i = (pbuffer - buffer); i < zero_pad; i++) + *(pbuffer++) = '0'; + + if (negative) + *(pbuffer++) = '-'; + + *(pbuffer) = '\0'; + + /* ... now we reverse it (could do it recursively but will + * conserve the stack space) */ + len = (pbuffer - buffer); + for (i = 0; i < len / 2; i++) { + char j = buffer[i]; + buffer[i] = buffer[len-i-1]; + buffer[len-i-1] = j; + } + + return len; +} + +struct mini_buff { + char *buffer, *pbuffer; + unsigned int buffer_len; +}; + +static int +_putc(int ch, struct mini_buff *b) +{ + if ((unsigned int)((b->pbuffer - b->buffer) + 1) >= b->buffer_len) + return 0; + *(b->pbuffer++) = ch; + *(b->pbuffer) = '\0'; + return 1; +} + +static int +_puts(char *s, unsigned int len, struct mini_buff *b) +{ + unsigned int i; + + if (b->buffer_len - (b->pbuffer - b->buffer) - 1 < len) + len = b->buffer_len - (b->pbuffer - b->buffer) - 1; + + /* Copy to buffer */ + for (i = 0; i < len; i++) + *(b->pbuffer++) = s[i]; + *(b->pbuffer) = '\0'; + + return len; +} + +int +mini_vsnprintf(char *buffer, unsigned int buffer_len, const char *fmt, va_list va) +{ + struct mini_buff b; + char bf[24]; + char ch; + + b.buffer = buffer; + b.pbuffer = buffer; + b.buffer_len = buffer_len; + + while ((ch=*(fmt++))) { + if ((unsigned int)((b.pbuffer - b.buffer) + 1) >= b.buffer_len) + break; + if (ch!='%') + _putc(ch, &b); + else { + char zero_pad = 0; + char *ptr; + unsigned int len; + + ch=*(fmt++); + + /* Zero padding requested */ + if (ch=='0') { + ch=*(fmt++); + if (ch == '\0') + goto end; + if (ch >= '0' && ch <= '9') + zero_pad = ch - '0'; + ch=*(fmt++); + } + + switch (ch) { + case 0: + goto end; + + case 'u': + case 'd': + len = mini_itoa(va_arg(va, unsigned int), 10, 0, (ch=='u'), bf, zero_pad); + _puts(bf, len, &b); + break; + + case 'x': + case 'X': + len = mini_itoa(va_arg(va, unsigned int), 16, (ch=='X'), 1, bf, zero_pad); + _puts(bf, len, &b); + break; + + case 'c' : + _putc((char)(va_arg(va, int)), &b); + break; + + case 's' : + ptr = va_arg(va, char*); + _puts(ptr, mini_strlen(ptr), &b); + break; + + default: + _putc(ch, &b); + break; + } + } + } +end: + return b.pbuffer - b.buffer; +} + + +int +mini_snprintf(char* buffer, unsigned int buffer_len, const char *fmt, ...) +{ + int ret; + va_list va; + va_start(va, fmt); + ret = mini_vsnprintf(buffer, buffer_len, fmt, va); + va_end(va); + + return ret; +} diff --git a/fw/mini-printf.h b/fw/mini-printf.h new file mode 100644 index 0000000..99a9519 --- /dev/null +++ b/fw/mini-printf.h @@ -0,0 +1,50 @@ +/* + * The Minimal snprintf() implementation + * + * Copyright (c) 2013 Michal Ludvig <michal@logix.cz> + * 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. + * * Neither the name of the auhor nor the names of its contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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 AUTHOR 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 __MINI_PRINTF__ +#define __MINI_PRINTF__ + +#ifdef __cplusplus +extern "C" { +#endif + +#include <stdarg.h> + +int mini_vsnprintf(char* buffer, unsigned int buffer_len, const char *fmt, va_list va); +int mini_snprintf(char* buffer, unsigned int buffer_len, const char *fmt, ...); + +#ifdef __cplusplus +} +#endif + +#define vsnprintf mini_vsnprintf +#define snprintf mini_snprintf + +#endif diff --git a/fw/openocd.cfg b/fw/openocd.cfg new file mode 100644 index 0000000..97a3a05 --- /dev/null +++ b/fw/openocd.cfg @@ -0,0 +1,14 @@ +telnet_port 4444 +gdb_port 3333 + +source [find interface/stlink-v2.cfg] +#hla_serial "000000000001" +transport select hla_swd + +source [find target/stm32f0x.cfg] +#adapter_khz 10000 + +init +arm semihosting enable + +#flash bank sysflash.alias stm32f0x 0x00000000 0 0 0 $_TARGETNAME diff --git a/fw/serial.c b/fw/serial.c new file mode 100644 index 0000000..1b25d7e --- /dev/null +++ b/fw/serial.c @@ -0,0 +1,233 @@ +/* 8seg LED display driver firmware + * Copyright (C) 2018 Sebastian Götte <code@jaseg.net> + * + * 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 3 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, see <http://www.gnu.org/licenses/>. + */ + +#include "serial.h" +#include "mac.h" + +unsigned int uart_overruns = 0; +unsigned int invalid_frames = 0; + +static union tx_buf_union tx_buf; +volatile union rx_buf_union rx_buf; + +void serial_init() { + USART1->CR1 = /* 8-bit -> M1, M0 clear */ + /* RTOIE clear */ + (8 << USART_CR1_DEAT_Pos) /* 8 sample cycles/1 bit DE assertion time */ + | (8 << USART_CR1_DEDT_Pos) /* 8 sample cycles/1 bit DE assertion time */ + /* OVER8 clear. Use default 16x oversampling */ + /* CMIF clear */ + | USART_CR1_MME + /* WAKE clear */ + /* PCE, PS clear */ + | USART_CR1_RXNEIE /* Enable receive interrupt */ + /* other interrupts clear */ + | USART_CR1_TE + | USART_CR1_RE; + /* Invert TX and DE to accomodate the level shifters */ + USART1->CR2 = USART_CR2_TXINV; + USART1->CR3 = USART_CR3_DEM | USART_CR3_DEP; /* enable RS485 DE (output on RTS) */ + /* Set divider for 9600 baud rate @48MHz system clock. */ + int usartdiv = 5000; + USART1->BRR = usartdiv; + + /* And... go! */ + USART1->CR1 |= USART_CR1_UE; + + /* Enable receive interrupt */ + NVIC_EnableIRQ(USART1_IRQn); + NVIC_SetPriority(USART1_IRQn, 1); +} + +void tx_char(uint8_t c) { + while (!(USART1->ISR & USART_ISR_TC)); + USART1->TDR = c; +} + +void send_frame_formatted(uint8_t *buf, int len) { + uint8_t *p=buf, *q=buf, *end=buf+len; + do { + while (*q && q!=end) + q++; + tx_char(q-p+1); + while (*p && p!=end) + tx_char(*p++); + p++, q++; + } while (p < end); + tx_char('\0'); +} + +void send_status_reply(void) { + tx_buf.desc_reply.firmware_version = FIRMWARE_VERSION; + tx_buf.desc_reply.hardware_version = HARDWARE_VERSION; + tx_buf.desc_reply.pad[0] = tx_buf.desc_reply.pad[1] = 0; + tx_buf.desc_reply.uptime_s = sys_time_s; + //tx_buf.desc_reply.vcc_mv = adc_vcc_mv; + //tx_buf.desc_reply.temp_celsius = adc_temp_celsius; + tx_buf.desc_reply.global_brightness = global_brightness; + tx_buf.desc_reply.framerate_millifps = frame_duration_us > 0 ? 1000000000 / frame_duration_us : 0; + tx_buf.desc_reply.uart_overruns = uart_overruns; + tx_buf.desc_reply.invalid_frames = invalid_frames; + send_frame_formatted(tx_buf.byte_data, sizeof(tx_buf.desc_reply)); +} + +/* This is the higher-level protocol handler for the serial protocol. It gets passed the number of data bytes in this + * frame (which may be zero) and returns a pointer to the buffer where the next frame should be stored. + */ +volatile uint8_t *packet_received(int len) { + static enum { + PROT_ADDRESSED = 0, + PROT_IGNORE = 2, + } protocol_state = PROT_IGNORE; + /* Use mac frames as delimiters to synchronize this protocol layer */ + trigger_comm_led(); + if (len == 0) { /* Discovery packet */ + if (sys_time_tick < 100) { /* Only respond during the first 100ms after boot */ + send_frame_formatted((uint8_t*)&device_mac, sizeof(device_mac)); + } + + } else if (len == 1) { /* Command packet */ + if (protocol_state == PROT_ADDRESSED) { + switch (rx_buf.byte_data[0]) { + case 0x01: + send_status_reply(); + break; + } + } else { + invalid_frames++; + trigger_error_led(); + } + protocol_state = PROT_IGNORE; + + } else if (len == 4) { /* Address packet */ + if (rx_buf.mac_data == device_mac) { /* we are addressed */ + protocol_state = PROT_ADDRESSED; /* start listening for frame buffer data */ + } else { /* we are not addressed */ + protocol_state = PROT_IGNORE; /* ignore packet */ + } + + } else if (len == sizeof(rx_buf.set_fb_rq)/2) { + if (protocol_state == PROT_ADDRESSED) { /* First of two half-framebuffer data frames */ + + /* FIXME */ + + /* Go to "hang mode" until next zero-length packet. */ + protocol_state = PROT_IGNORE; + } + + } else { + /* FIXME An invalid packet has been received. What should we do? */ + invalid_frames++; + trigger_error_led(); + protocol_state = PROT_IGNORE; /* go into "hang mode" until next zero-length packet */ + } + + /* By default, return rx_buf.byte_data . This means if an invalid protocol state is reached ("hang mode"), the next + * frame is still written to rx_buf. This is not a problem since whatever garbage is written at that point will be + * overwritten before the next buffer transfer. */ + return rx_buf.byte_data; +} + +void USART1_IRQHandler(void) { + /* Since a large amount of data will be shoved down this UART interface we need a more reliable and more efficient + * way of framing than just waiting between transmissions. + * + * This code uses "Consistent Overhead Byte Stuffing" (COBS). For details, see its Wikipedia page[0] or the proper + * scientific paper[1] published on it. Roughly, it works like this: + * + * * A frame is at most 254 bytes in length. + * * The null byte 0x00 acts as a frame delimiter. There is no null bytes inside frames. + * * Every frame starts with an "overhead" byte indicating the number of non-null payload bytes until the next null + * byte in the payload, **plus one**. This means this byte can never be zero. + * * Every null byte in the payload is replaced by *its* distance to *its* next null byte as above. + * + * This means, at any point the receiver can efficiently be synchronized on the next frame boundary by simply + * waiting for a null byte. After that, only a simple state machine is necessary to strip the overhead byte and a + * counter to then count skip intervals. + * + * Here is Wikipedia's table of example values: + * + * Unencoded data Encoded with COBS + * 00 01 01 00 + * 00 00 01 01 01 00 + * 11 22 00 33 03 11 22 02 33 00 + * 11 22 33 44 05 11 22 33 44 00 + * 11 00 00 00 02 11 01 01 01 00 + * 01 02 ...FE FF 01 02 ...FE 00 + * + * [0] https://en.wikipedia.org/wiki/Consistent_Overhead_Byte_Stuffing + * [1] Cheshire, Stuart; Baker, Mary (1999). "Consistent Overhead Byte Stuffing" + * IEEE/ACM Transactions on Networking. doi:10.1109/90.769765 + * http://www.stuartcheshire.org/papers/COBSforToN.pdf + */ + + /* This pointer stores where we write data. The higher-level protocol logic decides on a frame-by-frame-basis where + * the next frame's data will be stored. */ + static volatile uint8_t *writep = rx_buf.byte_data; + /* Index inside the current frame payload */ + static int rxpos = 0; + /* COBS state machine. This implementation might be a little too complicated, but it works well enough and I find it + * reasonably easy to understand. */ + static enum { + COBS_WAIT_SYNC = 0, /* Synchronize with frame */ + COBS_WAIT_START = 1, /* Await overhead byte */ + COBS_RUNNING = 2 /* Process payload */ + } cobs_state = 0; + /* COBS skip counter. During payload processing this contains the remaining non-null payload bytes */ + static int cobs_count = 0; + + if (USART1->ISR & USART_ISR_ORE) { /* Overrun handling */ + uart_overruns++; + trigger_error_led(); + /* Reset and re-synchronize. Retry next frame. */ + rxpos = 0; + cobs_state = COBS_WAIT_SYNC; + /* Clear interrupt flag */ + USART1->ICR = USART_ICR_ORECF; + + } else { /* Data received */ + uint8_t data = USART1->RDR; /* This automatically acknowledges the IRQ */ + + if (data == 0x00) { /* End-of-packet */ + /* Process higher protocol layers on this packet. */ + writep = packet_received(rxpos); + + /* Reset for next packet. */ + cobs_state = COBS_WAIT_START; + rxpos = 0; + + } else { /* non-null byte */ + if (cobs_state == COBS_WAIT_SYNC) { /* Wait for null byte */ + /* ignore data */ + + } else if (cobs_state == COBS_WAIT_START) { /* Overhead byte */ + cobs_count = data; + cobs_state = COBS_RUNNING; + + } else { /* Payload byte */ + if (--cobs_count == 0) { /* Skip byte */ + cobs_count = data; + data = 0; + } + + /* Write processed payload byte to current receive buffer */ + writep[rxpos++] = data; + } + } + } +} + diff --git a/fw/serial.h b/fw/serial.h new file mode 100644 index 0000000..8e2bf3d --- /dev/null +++ b/fw/serial.h @@ -0,0 +1,62 @@ +/* Megumin LED display firmware + * Copyright (C) 2018 Sebastian Götte <code@jaseg.net> + * + * 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 3 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, see <http://www.gnu.org/licenses/>. + */ + +#ifndef __SERIAL_H__ +#define __SERIAL_H__ + +#include "global.h" + +/* High-level stuff */ +void serial_init(void); +void send_status_reply(void); + +/* Internal low-level stuff */ +void tx_char(uint8_t c); +void send_frame_formatted(uint8_t *buf, int len); +volatile uint8_t *packet_received(int len); + +/* Error counters for debugging */ +extern unsigned int uart_overruns; +extern unsigned int invalid_frames; + +union tx_buf_union { + struct __attribute__((packed)) { + uint8_t firmware_version, + hardware_version, + pad[2]; + uint32_t uptime_s, + framerate_millifps, + uart_overruns, + invalid_frames; + int16_t vin_mv, + v3v3_mv, + iload_ma, + temp_celsius; + uint8_t global_brightness; + } desc_reply; + uint8_t byte_data[0]; +}; + +union rx_buf_union { + struct __attribute__((packed)) { uint8_t fb[32]; uint8_t end[0]; } set_fb_rq; + struct __attribute__((packed)) { uint8_t brightness; uint8_t end[0]; } set_global_brightness; + uint8_t byte_data[0]; + uint32_t mac_data; +}; +extern volatile union rx_buf_union rx_buf; + +#endif/*__SERIAL_H__*/ diff --git a/fw/startup_stm32f030x6.s b/fw/startup_stm32f030x6.s new file mode 100644 index 0000000..2f0eb42 --- /dev/null +++ b/fw/startup_stm32f030x6.s @@ -0,0 +1,273 @@ +/**
+ ******************************************************************************
+ * @file startup_stm32f030x6.s
+ * copied from: STM32Cube/Drivers/CMSIS/Device/ST/STM32F0xx/Source/Templates/gcc
+ * @author MCD Application Team
+ * @version V2.3.1
+ * @date 04-November-2016
+ * @brief STM32F030x4/STM32F030x6 devices vector table for Atollic TrueSTUDIO toolchain.
+ * This module performs:
+ * - Set the initial SP
+ * - Set the initial PC == Reset_Handler,
+ * - Set the vector table entries with the exceptions ISR address
+ * - Branches to main in the C library (which eventually
+ * calls main()).
+ * After Reset the Cortex-M0 processor is in Thread mode,
+ * priority is Privileged, and the Stack is set to Main.
+ ******************************************************************************
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. 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.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * 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.
+ *
+ ******************************************************************************
+ */
+
+ .syntax unified
+ .cpu cortex-m0
+ .fpu softvfp
+ .thumb
+
+.global g_pfnVectors
+.global Default_Handler
+
+/* start address for the initialization values of the .data section.
+defined in linker script */
+.word _sidata
+/* start address for the .data section. defined in linker script */
+.word _sdata
+/* end address for the .data section. defined in linker script */
+.word _edata
+/* start address for the .bss section. defined in linker script */
+.word _sbss
+/* end address for the .bss section. defined in linker script */
+.word _ebss
+
+ .section .text.Reset_Handler
+ .weak Reset_Handler
+ .type Reset_Handler, %function
+Reset_Handler:
+ ldr r0, =_estack
+ mov sp, r0 /* set stack pointer */
+
+/* Copy the data segment initializers from flash to SRAM */
+ movs r1, #0
+ b LoopCopyDataInit
+
+CopyDataInit:
+ ldr r3, =_sidata
+ ldr r3, [r3, r1]
+ str r3, [r0, r1]
+ adds r1, r1, #4
+
+LoopCopyDataInit:
+ ldr r0, =_sdata
+ ldr r3, =_edata
+ adds r2, r0, r1
+ cmp r2, r3
+ bcc CopyDataInit
+ ldr r2, =_sbss
+ b LoopFillZerobss
+/* Zero fill the bss segment. */
+FillZerobss:
+ movs r3, #0
+ str r3, [r2]
+ adds r2, r2, #4
+
+
+LoopFillZerobss:
+ ldr r3, = _ebss
+ cmp r2, r3
+ bcc FillZerobss
+
+/* Call the clock system intitialization function.*/
+ bl SystemInit
+/* Call static constructors */
+// bl __libc_init_array
+/* Call the application's entry point.*/
+ bl main
+
+LoopForever:
+ b LoopForever
+
+
+.size Reset_Handler, .-Reset_Handler
+
+/**
+ * @brief This is the code that gets called when the processor receives an
+ * unexpected interrupt. This simply enters an infinite loop, preserving
+ * the system state for examination by a debugger.
+ *
+ * @param None
+ * @retval : None
+*/
+ .section .text.Default_Handler,"ax",%progbits
+Default_Handler:
+Infinite_Loop:
+ b Infinite_Loop
+ .size Default_Handler, .-Default_Handler
+/******************************************************************************
+*
+* The minimal vector table for a Cortex M0. Note that the proper constructs
+* must be placed on this to ensure that it ends up at physical address
+* 0x0000.0000.
+*
+******************************************************************************/
+ .section .isr_vector,"a",%progbits
+ .type g_pfnVectors, %object
+ .size g_pfnVectors, .-g_pfnVectors
+
+
+g_pfnVectors:
+ .word _estack
+ .word Reset_Handler
+ .word NMI_Handler
+ .word HardFault_Handler
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word 0
+ .word SVC_Handler
+ .word 0
+ .word 0
+ .word PendSV_Handler
+ .word SysTick_Handler
+ .word WWDG_IRQHandler /* Window WatchDog */
+ .word 0 /* Reserved */
+ .word RTC_IRQHandler /* RTC through the EXTI line */
+ .word FLASH_IRQHandler /* FLASH */
+ .word RCC_IRQHandler /* RCC */
+ .word EXTI0_1_IRQHandler /* EXTI Line 0 and 1 */
+ .word EXTI2_3_IRQHandler /* EXTI Line 2 and 3 */
+ .word EXTI4_15_IRQHandler /* EXTI Line 4 to 15 */
+ .word 0 /* Reserved */
+ .word DMA1_Channel1_IRQHandler /* DMA1 Channel 1 */
+ .word DMA1_Channel2_3_IRQHandler /* DMA1 Channel 2 and Channel 3 */
+ .word DMA1_Channel4_5_IRQHandler /* DMA1 Channel 4 and Channel 5 */
+ .word ADC1_IRQHandler /* ADC1 */
+ .word TIM1_BRK_UP_TRG_COM_IRQHandler /* TIM1 Break, Update, Trigger and Commutation */
+ .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */
+ .word 0 /* Reserved */
+ .word TIM3_IRQHandler /* TIM3 */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word TIM14_IRQHandler /* TIM14 */
+ .word 0 /* Reserved */
+ .word TIM16_IRQHandler /* TIM16 */
+ .word TIM17_IRQHandler /* TIM17 */
+ .word I2C1_IRQHandler /* I2C1 */
+ .word 0 /* Reserved */
+ .word SPI1_IRQHandler /* SPI1 */
+ .word 0 /* Reserved */
+ .word USART1_IRQHandler /* USART1 */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+ .word 0 /* Reserved */
+
+/*******************************************************************************
+*
+* Provide weak aliases for each Exception handler to the Default_Handler.
+* As they are weak aliases, any function with the same name will override
+* this definition.
+*
+*******************************************************************************/
+
+ .weak NMI_Handler
+ .thumb_set NMI_Handler,Default_Handler
+
+ .weak HardFault_Handler
+ .thumb_set HardFault_Handler,Default_Handler
+
+ .weak SVC_Handler
+ .thumb_set SVC_Handler,Default_Handler
+
+ .weak PendSV_Handler
+ .thumb_set PendSV_Handler,Default_Handler
+
+ .weak SysTick_Handler
+ .thumb_set SysTick_Handler,Default_Handler
+
+ .weak WWDG_IRQHandler
+ .thumb_set WWDG_IRQHandler,Default_Handler
+
+ .weak RTC_IRQHandler
+ .thumb_set RTC_IRQHandler,Default_Handler
+
+ .weak FLASH_IRQHandler
+ .thumb_set FLASH_IRQHandler,Default_Handler
+
+ .weak RCC_IRQHandler
+ .thumb_set RCC_IRQHandler,Default_Handler
+
+ .weak EXTI0_1_IRQHandler
+ .thumb_set EXTI0_1_IRQHandler,Default_Handler
+
+ .weak EXTI2_3_IRQHandler
+ .thumb_set EXTI2_3_IRQHandler,Default_Handler
+
+ .weak EXTI4_15_IRQHandler
+ .thumb_set EXTI4_15_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel1_IRQHandler
+ .thumb_set DMA1_Channel1_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel2_3_IRQHandler
+ .thumb_set DMA1_Channel2_3_IRQHandler,Default_Handler
+
+ .weak DMA1_Channel4_5_IRQHandler
+ .thumb_set DMA1_Channel4_5_IRQHandler,Default_Handler
+
+ .weak ADC1_IRQHandler
+ .thumb_set ADC1_IRQHandler,Default_Handler
+
+ .weak TIM1_BRK_UP_TRG_COM_IRQHandler
+ .thumb_set TIM1_BRK_UP_TRG_COM_IRQHandler,Default_Handler
+
+ .weak TIM1_CC_IRQHandler
+ .thumb_set TIM1_CC_IRQHandler,Default_Handler
+
+ .weak TIM3_IRQHandler
+ .thumb_set TIM3_IRQHandler,Default_Handler
+
+ .weak TIM14_IRQHandler
+ .thumb_set TIM14_IRQHandler,Default_Handler
+
+ .weak TIM16_IRQHandler
+ .thumb_set TIM16_IRQHandler,Default_Handler
+
+ .weak TIM17_IRQHandler
+ .thumb_set TIM17_IRQHandler,Default_Handler
+
+ .weak I2C1_IRQHandler
+ .thumb_set I2C1_IRQHandler,Default_Handler
+
+ .weak SPI1_IRQHandler
+ .thumb_set SPI1_IRQHandler,Default_Handler
+
+ .weak USART1_IRQHandler
+ .thumb_set USART1_IRQHandler,Default_Handler
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
diff --git a/fw/stm32_flash.ld b/fw/stm32_flash.ld new file mode 100644 index 0000000..cba7577 --- /dev/null +++ b/fw/stm32_flash.ld @@ -0,0 +1,136 @@ +
+ENTRY(Reset_Handler)
+
+MEMORY {
+ FLASH (rx): ORIGIN = 0x08000000, LENGTH = 0x3C00
+ CONFIGFLASH (rw): ORIGIN = 0x08003C00, LENGTH = 0x400
+ RAM (xrw): ORIGIN = 0x20000000, LENGTH = 4K
+}
+
+/* highest address of the user mode stack */
+_estack = 0x20001000;
+
+SECTIONS {
+ /* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to FLASH */
+ .isr_vector : {
+ . = ALIGN(4);
+ KEEP(*(.isr_vector)) /* Startup code */
+ . = ALIGN(4);
+ } >FLASH
+
+ /* the program code is stored in the .text section, which goes to Flash */
+ .text : {
+ . = ALIGN(4);
+
+ *(.text) /* normal code */
+ *(.text.*) /* -ffunction-sections code */
+ *(.rodata) /* read-only data (constants) */
+ *(.rodata*) /* -fdata-sections read only data */
+ *(.glue_7) /* TBD - needed ? */
+ *(.glue_7t) /* TBD - needed ? */
+
+ *(.source_tarball)
+
+ /* Necessary KEEP sections (see http://sourceware.org/ml/newlib/2005/msg00255.html) */
+ KEEP (*(.init))
+ KEEP (*(.fini))
+ KEEP (*(.source_tarball))
+
+ . = ALIGN(4);
+ _etext = .;
+ /* This is used by the startup in order to initialize the .data section */
+ _sidata = _etext;
+ } >FLASH
+
+ /*
+ .configflash : {
+ . = ALIGN(0x400);
+ *(.configdata)
+ _econfig = .;
+ } >FLASH
+ */
+
+ /* This is the initialized data section
+ The program executes knowing that the data is in the RAM
+ but the loader puts the initial values in the FLASH (inidata).
+ It is one task of the startup to copy the initial values from FLASH to RAM. */
+ .data : AT ( _sidata ) {
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .data secion */
+ _sdata = . ;
+ _data = . ;
+
+ *(.data)
+ *(.data.*)
+ *(.RAMtext)
+
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .data secion */
+ _edata = . ;
+ } >RAM
+
+ /* This is the uninitialized data section */
+ .bss : {
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .bss secion */
+ _sbss = .;
+ _bss = .;
+
+ *(.bss)
+ *(.bss.*) /* patched by elias - allows the use of -fdata-sections */
+ *(COMMON)
+
+ . = ALIGN(4);
+ /* This is used by the startup in order to initialize the .bss secion */
+ _ebss = . ;
+ } >RAM
+
+ PROVIDE ( end = _ebss);
+ PROVIDE (_end = _ebss);
+
+ __exidx_start = .;
+ __exidx_end = .;
+
+ /* after that it's only debugging information. */
+
+ /* remove the debugging information from the standard libraries */
+/* /DISCARD/ : {
+ libc.a ( * )
+ libm.a ( * )
+ libgcc.a ( * )
+ }*/
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ /* DWARF debug sections.
+ Symbols in the DWARF debugging sections are relative to the beginning
+ of the section so we begin them at 0. */
+ /* DWARF 1 */
+ .debug 0 : { *(.debug) }
+ .line 0 : { *(.line) }
+ /* GNU DWARF 1 extensions */
+ .debug_srcinfo 0 : { *(.debug_srcinfo) }
+ .debug_sfnames 0 : { *(.debug_sfnames) }
+ /* DWARF 1.1 and DWARF 2 */
+ .debug_aranges 0 : { *(.debug_aranges) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ /* DWARF 2 */
+ .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_frame 0 : { *(.debug_frame) }
+ .debug_str 0 : { *(.debug_str) }
+ .debug_loc 0 : { *(.debug_loc) }
+ .debug_macinfo 0 : { *(.debug_macinfo) }
+ /* SGI/MIPS DWARF 2 extensions */
+ .debug_weaknames 0 : { *(.debug_weaknames) }
+ .debug_funcnames 0 : { *(.debug_funcnames) }
+ .debug_typenames 0 : { *(.debug_typenames) }
+ .debug_varnames 0 : { *(.debug_varnames) }
+}
diff --git a/fw/system_stm32f0xx.c b/fw/system_stm32f0xx.c new file mode 100644 index 0000000..a43c3d6 --- /dev/null +++ b/fw/system_stm32f0xx.c @@ -0,0 +1,336 @@ +/**
+ ******************************************************************************
+ * @file system_stm32f0xx.c
+ * copied from: STM32Cube/Drivers/CMSIS/Device/ST/STM32F0xx/Source/Templates
+ * @author MCD Application Team
+ * @version V2.3.1
+ * @date 04-November-2016
+ * @brief CMSIS Cortex-M0 Device Peripheral Access Layer System Source File.
+ *
+ * 1. This file provides two functions and one global variable to be called from
+ * user application:
+ * - SystemInit(): This function is called at startup just after reset and
+ * before branch to main program. This call is made inside
+ * the "startup_stm32f0xx.s" file.
+ *
+ * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
+ * by the user application to setup the SysTick
+ * timer or configure other parameters.
+ *
+ * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
+ * be called whenever the core clock is changed
+ * during program execution.
+ *
+ * 2. After each device reset the HSI (8 MHz) is used as system clock source.
+ * Then SystemInit() function is called, in "startup_stm32f0xx.s" file, to
+ * configure the system clock before to branch to main program.
+ *
+ * 3. This file configures the system clock as follows:
+ *=============================================================================
+ * Supported STM32F0xx device
+ *-----------------------------------------------------------------------------
+ * System Clock source | HSI
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 8000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 8000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>© COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
+ *
+ * Redistribution and use in source and binary forms, with or without modification,
+ * are permitted provided that the following conditions are met:
+ * 1. Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ * 2. 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.
+ * 3. Neither the name of STMicroelectronics nor the names of its contributors
+ * may be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * 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.
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32f0xx_system
+ * @{
+ */
+
+/** @addtogroup STM32F0xx_System_Private_Includes
+ * @{
+ */
+
+#include "stm32f0xx.h"
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F0xx_System_Private_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F0xx_System_Private_Defines
+ * @{
+ */
+#if !defined (HSE_VALUE)
+ #define HSE_VALUE ((uint32_t)8000000) /*!< Default value of the External oscillator in Hz.
+ This value can be provided and adapted by the user application. */
+#endif /* HSE_VALUE */
+
+#if !defined (HSI_VALUE)
+ #define HSI_VALUE ((uint32_t)8000000) /*!< Default value of the Internal oscillator in Hz.
+ This value can be provided and adapted by the user application. */
+#endif /* HSI_VALUE */
+
+#if !defined (HSI48_VALUE)
+#define HSI48_VALUE ((uint32_t)48000000) /*!< Default value of the HSI48 Internal oscillator in Hz.
+ This value can be provided and adapted by the user application. */
+#endif /* HSI48_VALUE */
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F0xx_System_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F0xx_System_Private_Variables
+ * @{
+ */
+ /* This variable is updated in three ways:
+ 1) by calling CMSIS function SystemCoreClockUpdate()
+ 2) by calling HAL API function HAL_RCC_GetHCLKFreq()
+ 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency
+ Note: If you use this function to configure the system clock there is no need to
+ call the 2 first functions listed above, since SystemCoreClock variable is
+ updated automatically.
+ */
+uint32_t SystemCoreClock = 8000000;
+
+const uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
+const uint8_t APBPrescTable[8] = {0, 0, 0, 0, 1, 2, 3, 4};
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F0xx_System_Private_FunctionPrototypes
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F0xx_System_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Setup the microcontroller system.
+ * Initialize the default HSI clock source, vector table location and the PLL configuration is reset.
+ * @param None
+ * @retval None
+ */
+void SystemInit(void)
+{
+ /* Reset the RCC clock configuration to the default reset state ------------*/
+ /* Set HSION bit */
+ RCC->CR |= (uint32_t)0x00000001U;
+
+#if defined (STM32F051x8) || defined (STM32F058x8)
+ /* Reset SW[1:0], HPRE[3:0], PPRE[2:0], ADCPRE and MCOSEL[2:0] bits */
+ RCC->CFGR &= (uint32_t)0xF8FFB80CU;
+#else
+ /* Reset SW[1:0], HPRE[3:0], PPRE[2:0], ADCPRE, MCOSEL[2:0], MCOPRE[2:0] and PLLNODIV bits */
+ RCC->CFGR &= (uint32_t)0x08FFB80CU;
+#endif /* STM32F051x8 or STM32F058x8 */
+
+ /* Reset HSEON, CSSON and PLLON bits */
+ RCC->CR &= (uint32_t)0xFEF6FFFFU;
+
+ /* Reset HSEBYP bit */
+ RCC->CR &= (uint32_t)0xFFFBFFFFU;
+
+ /* Reset PLLSRC, PLLXTPRE and PLLMUL[3:0] bits */
+ RCC->CFGR &= (uint32_t)0xFFC0FFFFU;
+
+ /* Reset PREDIV[3:0] bits */
+ RCC->CFGR2 &= (uint32_t)0xFFFFFFF0U;
+
+#if defined (STM32F072xB) || defined (STM32F078xx)
+ /* Reset USART2SW[1:0], USART1SW[1:0], I2C1SW, CECSW, USBSW and ADCSW bits */
+ RCC->CFGR3 &= (uint32_t)0xFFFCFE2CU;
+#elif defined (STM32F071xB)
+ /* Reset USART2SW[1:0], USART1SW[1:0], I2C1SW, CECSW and ADCSW bits */
+ RCC->CFGR3 &= (uint32_t)0xFFFFCEACU;
+#elif defined (STM32F091xC) || defined (STM32F098xx)
+ /* Reset USART3SW[1:0], USART2SW[1:0], USART1SW[1:0], I2C1SW, CECSW and ADCSW bits */
+ RCC->CFGR3 &= (uint32_t)0xFFF0FEACU;
+#elif defined (STM32F030x6) || defined (STM32F030x8) || defined (STM32F031x6) || defined (STM32F038xx) || defined (STM32F030xC)
+ /* Reset USART1SW[1:0], I2C1SW and ADCSW bits */
+ RCC->CFGR3 &= (uint32_t)0xFFFFFEECU;
+#elif defined (STM32F051x8) || defined (STM32F058xx)
+ /* Reset USART1SW[1:0], I2C1SW, CECSW and ADCSW bits */
+ RCC->CFGR3 &= (uint32_t)0xFFFFFEACU;
+#elif defined (STM32F042x6) || defined (STM32F048xx)
+ /* Reset USART1SW[1:0], I2C1SW, CECSW, USBSW and ADCSW bits */
+ RCC->CFGR3 &= (uint32_t)0xFFFFFE2CU;
+#elif defined (STM32F070x6) || defined (STM32F070xB)
+ /* Reset USART1SW[1:0], I2C1SW, USBSW and ADCSW bits */
+ RCC->CFGR3 &= (uint32_t)0xFFFFFE6CU;
+ /* Set default USB clock to PLLCLK, since there is no HSI48 */
+ RCC->CFGR3 |= (uint32_t)0x00000080U;
+#else
+ #warning "No target selected"
+#endif
+
+ /* Reset HSI14 bit */
+ RCC->CR2 &= (uint32_t)0xFFFFFFFEU;
+
+ /* Disable all interrupts */
+ RCC->CIR = 0x00000000U;
+
+}
+
+/**
+ * @brief Update SystemCoreClock variable according to Clock Register Values.
+ * The SystemCoreClock variable contains the core clock (HCLK), it can
+ * be used by the user application to setup the SysTick timer or configure
+ * other parameters.
+ *
+ * @note Each time the core clock (HCLK) changes, this function must be called
+ * to update SystemCoreClock variable value. Otherwise, any configuration
+ * based on this variable will be incorrect.
+ *
+ * @note - The system frequency computed by this function is not the real
+ * frequency in the chip. It is calculated based on the predefined
+ * constant and the selected clock source:
+ *
+ * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
+ *
+ * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
+ *
+ * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
+ * or HSI_VALUE(*) multiplied/divided by the PLL factors.
+ *
+ * (*) HSI_VALUE is a constant defined in stm32f0xx_hal.h file (default value
+ * 8 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ *
+ * (**) HSE_VALUE is a constant defined in stm32f0xx_hal.h file (default value
+ * 8 MHz), user has to ensure that HSE_VALUE is same as the real
+ * frequency of the crystal used. Otherwise, this function may
+ * have wrong result.
+ *
+ * - The result of this function could be not correct when using fractional
+ * value for HSE crystal.
+ *
+ * @param None
+ * @retval None
+ */
+void SystemCoreClockUpdate (void)
+{
+ uint32_t tmp = 0, pllmull = 0, pllsource = 0, predivfactor = 0;
+
+ /* Get SYSCLK source -------------------------------------------------------*/
+ tmp = RCC->CFGR & RCC_CFGR_SWS;
+
+ switch (tmp)
+ {
+ case RCC_CFGR_SWS_HSI: /* HSI used as system clock */
+ SystemCoreClock = HSI_VALUE;
+ break;
+ case RCC_CFGR_SWS_HSE: /* HSE used as system clock */
+ SystemCoreClock = HSE_VALUE;
+ break;
+ case RCC_CFGR_SWS_PLL: /* PLL used as system clock */
+ /* Get PLL clock source and multiplication factor ----------------------*/
+ pllmull = RCC->CFGR & RCC_CFGR_PLLMUL;
+ pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
+ pllmull = ( pllmull >> 18) + 2;
+ predivfactor = (RCC->CFGR2 & RCC_CFGR2_PREDIV) + 1;
+
+ if (pllsource == RCC_CFGR_PLLSRC_HSE_PREDIV)
+ {
+ /* HSE used as PLL clock source : SystemCoreClock = HSE/PREDIV * PLLMUL */
+ SystemCoreClock = (HSE_VALUE/predivfactor) * pllmull;
+ }
+#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F072xB) || defined(STM32F078xx) || defined(STM32F091xC) || defined(STM32F098xx)
+ else if (pllsource == RCC_CFGR_PLLSRC_HSI48_PREDIV)
+ {
+ /* HSI48 used as PLL clock source : SystemCoreClock = HSI48/PREDIV * PLLMUL */
+ SystemCoreClock = (HSI48_VALUE/predivfactor) * pllmull;
+ }
+#endif /* STM32F042x6 || STM32F048xx || STM32F072xB || STM32F078xx || STM32F091xC || STM32F098xx */
+ else
+ {
+#if defined(STM32F042x6) || defined(STM32F048xx) || defined(STM32F070x6) \
+ || defined(STM32F078xx) || defined(STM32F071xB) || defined(STM32F072xB) \
+ || defined(STM32F070xB) || defined(STM32F091xC) || defined(STM32F098xx) || defined(STM32F030xC)
+ /* HSI used as PLL clock source : SystemCoreClock = HSI/PREDIV * PLLMUL */
+ SystemCoreClock = (HSI_VALUE/predivfactor) * pllmull;
+#else
+ /* HSI used as PLL clock source : SystemCoreClock = HSI/2 * PLLMUL */
+ SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
+#endif /* STM32F042x6 || STM32F048xx || STM32F070x6 ||
+ STM32F071xB || STM32F072xB || STM32F078xx || STM32F070xB ||
+ STM32F091xC || STM32F098xx || STM32F030xC */
+ }
+ break;
+ default: /* HSI used as system clock */
+ SystemCoreClock = HSI_VALUE;
+ break;
+ }
+ /* Compute HCLK clock frequency ----------------*/
+ /* Get HCLK prescaler */
+ tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
+ /* HCLK clock frequency */
+ SystemCoreClock >>= tmp;
+}
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
+
|