aboutsummaryrefslogtreecommitdiff
path: root/driver_fw
diff options
context:
space:
mode:
authorjaseg <git@jaseg.net>2019-04-14 13:25:23 +0900
committerjaseg <git@jaseg.net>2019-04-14 13:25:23 +0900
commit668c89f88988e4bd6149fa7d13650254037f028d (patch)
treedbd2188c7f15fd2756de1e5d79b9ce569c0f4cd4 /driver_fw
parent010d5587b776030690a2ab25902fe9eff52fcf5b (diff)
download8seg-668c89f88988e4bd6149fa7d13650254037f028d.tar.gz
8seg-668c89f88988e4bd6149fa7d13650254037f028d.tar.bz2
8seg-668c89f88988e4bd6149fa7d13650254037f028d.zip
driver/fw: I2C LCD working
Diffstat (limited to 'driver_fw')
-rw-r--r--driver_fw/Makefile2
-rw-r--r--driver_fw/global.h58
-rw-r--r--driver_fw/i2c.c236
-rw-r--r--driver_fw/i2c.h146
-rw-r--r--driver_fw/lcd1602.c183
-rw-r--r--driver_fw/lcd1602.h95
-rw-r--r--driver_fw/mac.c3
-rw-r--r--driver_fw/mac.h22
-rw-r--r--driver_fw/main.c22
-rw-r--r--driver_fw/serial.c233
-rw-r--r--driver_fw/serial.h62
11 files changed, 1060 insertions, 2 deletions
diff --git a/driver_fw/Makefile b/driver_fw/Makefile
index 749ec51..cfbe654 100644
--- a/driver_fw/Makefile
+++ b/driver_fw/Makefile
@@ -50,7 +50,7 @@ cmsis_exports.c: $(CMSIS_DEV_PATH)/Include/stm32f030x6.h $(CMSIS_PATH)/Include/c
%.dot: %.elf
r2 -a arm -qc 'aa;agC' $< 2>/dev/null >$@
-main.elf: main.o startup_stm32f030x6.o system_stm32f0xx.o $(HAL_PATH)/Src/stm32f0xx_ll_utils.o cmsis_exports.o ../common/8b10b.o serial.o mac.o
+main.elf: main.o startup_stm32f030x6.o system_stm32f0xx.o $(HAL_PATH)/Src/stm32f0xx_ll_utils.o cmsis_exports.o ../common/8b10b.o serial.o mac.o i2c.o lcd1602.o
$(CC) $(CFLAGS) $(LDFLAGS) -o $@ $^ $(LIBS)
$(OBJCOPY) -O ihex $@ $(@:.elf=.hex)
$(OBJCOPY) -O binary $@ $(@:.elf=.bin)
diff --git a/driver_fw/global.h b/driver_fw/global.h
new file mode 100644
index 0000000..4753543
--- /dev/null
+++ b/driver_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/driver_fw/i2c.c b/driver_fw/i2c.c
new file mode 100644
index 0000000..bab1a16
--- /dev/null
+++ b/driver_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/driver_fw/i2c.h b/driver_fw/i2c.h
new file mode 100644
index 0000000..ac4674d
--- /dev/null
+++ b/driver_fw/i2c.h
@@ -0,0 +1,146 @@
+#ifndef __I2C_H
+#define __I2C_H
+
+#include "global.h"
+
+// I2C HAL
+
+// I2C1
+// SCL [PB6, PB8]
+#define I2C1_SCL_GPIO_PERIPH RCC_AHB2ENR_GPIOBEN
+#define I2C1_SCL_GPIO_PORT GPIOB
+#define I2C1_SCL_GPIO_PIN GPIO_PIN_8
+#define I2C1_SCL_GPIO_SRC GPIO_PinSource8
+// SDA [PB7, PB9]
+#define I2C1_SDA_GPIO_PERIPH RCC_AHB2ENR_GPIOBEN
+#define I2C1_SDA_GPIO_PORT GPIOB
+#define I2C1_SDA_GPIO_PIN GPIO_PIN_9
+#define I2C1_SDA_GPIO_SRC GPIO_PinSource9
+
+// I2C2
+// SCL [PB10, PB13]
+#define I2C2_SCL_GPIO_PERIPH RCC_AHB2ENR_GPIOBEN
+#define I2C2_SCL_GPIO_PORT GPIOB
+#define I2C2_SCL_GPIO_PIN GPIO_PIN_10
+#define I2C2_SCL_GPIO_SRC GPIO_PinSource10
+// SDA [PB11, PB14]
+#define I2C2_SDA_GPIO_PERIPH RCC_AHB2ENR_GPIOBEN
+#define I2C2_SDA_GPIO_PORT GPIOB
+#define I2C2_SDA_GPIO_PIN GPIO_PIN_11
+#define I2C2_SDA_GPIO_SRC GPIO_PinSource11
+
+// I2C3
+// SCL [PC0]
+#define I2C3_SCL_GPIO_PERIPH RCC_AHB2ENR_GPIOCEN
+#define I2C3_SCL_GPIO_PORT GPIOC
+#define I2C3_SCL_GPIO_PIN GPIO_PIN_0
+#define I2C3_SCL_GPIO_SRC GPIO_PinSource0
+// SDA [PC1]
+#define I2C3_SDA_GPIO_PERIPH RCC_AHB2ENR_GPIOCEN
+#define I2C3_SDA_GPIO_PORT GPIOC
+#define I2C3_SDA_GPIO_PIN GPIO_PIN_1
+#define I2C3_SDA_GPIO_SRC GPIO_PinSource1
+
+
+// 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/driver_fw/lcd1602.c b/driver_fw/lcd1602.c
new file mode 100644
index 0000000..f065afc
--- /dev/null
+++ b/driver_fw/lcd1602.c
@@ -0,0 +1,183 @@
+/*
+ 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(15000);
+ send_half_byte(LCD_INITIALIZATION);
+ delay_micro(4000);
+ send_half_byte(LCD_INITIALIZATION);
+ delay_micro(100000);
+ send_half_byte(LCD_INITIALIZATION);
+ delay_micro(1000);
+ 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(1530);
+};
+
+/*
+ Отправка байта на шину
+ на входе: 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);
+};
+
+/*
+ Отправка половины байта экрану
+ на входе: 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/driver_fw/lcd1602.h b/driver_fw/lcd1602.h
new file mode 100644
index 0000000..70b324e
--- /dev/null
+++ b/driver_fw/lcd1602.h
@@ -0,0 +1,95 @@
+/*
+ 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
+
+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/driver_fw/mac.c b/driver_fw/mac.c
new file mode 100644
index 0000000..b2fb48a
--- /dev/null
+++ b/driver_fw/mac.c
@@ -0,0 +1,3 @@
+#include "mac.h"
+
+uint32_t device_mac = MAC_ADDR;
diff --git a/driver_fw/mac.h b/driver_fw/mac.h
new file mode 100644
index 0000000..26aaff6
--- /dev/null
+++ b/driver_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/driver_fw/main.c b/driver_fw/main.c
index ee4a4ed..8551d83 100644
--- a/driver_fw/main.c
+++ b/driver_fw/main.c
@@ -1,6 +1,8 @@
#include "global.h"
#include "serial.h"
+#include "i2c.h"
+#include "lcd1602.h"
#include <8b10b.h>
@@ -102,6 +104,15 @@ int main(void) {
GPIOA->ODR = 0; /* Set PA4 ODR to 0 */
+ GPIOA->OTYPER |=
+ GPIO_OTYPER_OT_1
+ | GPIO_OTYPER_OT_2;
+
+ // FIXME lag 37.3us @ 720 Ohm / 16.0us @ 360 Ohm / 2.8us @ 88 Ohm
+ GPIOA->OSPEEDR |=
+ (3<<GPIO_OSPEEDR_OSPEEDR1_Pos)
+ | (3<<GPIO_OSPEEDR_OSPEEDR2_Pos);
+
/* 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. */
@@ -112,7 +123,6 @@ int main(void) {
serial_init();
/* FIXME ADC config */
- /* FIXME I2C config, drivers for LCD & current sensor */
/* SPI config. SPI1 is used to control the shift register controlling the eight status LEDs. */
SPI1->CR2 = (7<<SPI_CR2_DS_Pos);
@@ -125,6 +135,16 @@ int main(void) {
| SPI_CR1_MSTR;
SPI1->CR1 |= SPI_CR1_SPE;
+ /* I2C for LCD, temp sensor, current sensor */
+ i2c_config_filters(I2C1, I2C_AF_ENABLE, 0);
+ i2c_config_timing(I2C1, 0x2000090e); /* Magic value for 100kHz I2C @ 48MHz CLK. Fell 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, "Hello World!");
+
/* TIM3 is used to generate the MOSFET driver control signals */
/* TIM3 running off 48MHz APB1 clk, T=20.833ns */
TIM3->CR1 = 0; /* Disable ARR preload (double-buffering) */
diff --git a/driver_fw/serial.c b/driver_fw/serial.c
new file mode 100644
index 0000000..efbcb95
--- /dev/null
+++ b/driver_fw/serial.c
@@ -0,0 +1,233 @@
+/* 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/>.
+ */
+
+#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/driver_fw/serial.h b/driver_fw/serial.h
new file mode 100644
index 0000000..8e2bf3d
--- /dev/null
+++ b/driver_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__*/