aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--CMakeLists.txt7
-rw-r--r--fdl/ch573/adc.fdl97
-rw-r--r--fdl/ch573/gpio.fdl39
-rw-r--r--include/gpio.h14
-rw-r--r--include/pattern.h5
-rw-r--r--include/risc-v.h45
-rw-r--r--include/task.h9
-rw-r--r--include/voltdisc.h19
-rw-r--r--include/ws2812b.h12
-rw-r--r--src/exc.c47
-rw-r--r--src/gpio.c35
-rw-r--r--src/init.c16
-rw-r--r--src/ir.c9
-rw-r--r--src/main.c52
-rw-r--r--src/patterns/candycane.c53
-rw-r--r--src/patterns/twinkle.c148
-rw-r--r--src/spi.c61
-rw-r--r--src/voltdisc.c44
-rw-r--r--src/ws2812b.c52
-rw-r--r--stubs/libgloss.abin0 -> 844 bytes
20 files changed, 593 insertions, 171 deletions
diff --git a/CMakeLists.txt b/CMakeLists.txt
index be194aa..554dfa4 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -49,8 +49,8 @@ project (ch537 LANGUAGES C ASM)
# Set compiler and linker flags
file(GLOB LINKER_SCRIPT "linker/*.ld")
-set(CMAKE_C_FLAGS "-march=rv32imac_zicsr -mabi=ilp32 -lgcc -static -O -std=gnu99" CACHE INTERNAL "C Compiler options")
-set(CMAKE_ASM_FLAGS "-march=rv32imac_zicsr -mabi=ilp32 -lgcc -static -O -std=gnu99" CACHE INTERNAL "C Compiler options")
+set(CMAKE_C_FLAGS "-march=rv32imac_zicsr -mabi=ilp32 -lgcc -static -Os -std=gnu99" CACHE INTERNAL "C Compiler options")
+set(CMAKE_ASM_FLAGS "-march=rv32imac_zicsr -mabi=ilp32 -lgcc -static -Os -std=gnu99" CACHE INTERNAL "C Compiler options")
set(CMAKE_EXE_LINKER_FLAGS "-static -L ${CMAKE_BINARY_DIR}/lib -lmain -T ${LINKER_SCRIPT}" CACHE INTERNAL "Linker options")
include_directories(include linker ${CMAKE_BINARY_DIR}/generated/fdl)
@@ -78,7 +78,7 @@ add_dependencies(libmain fdl_headers)
set(fdl_headers)
file(GLOB_RECURSE fdl_files "${CMAKE_SOURCE_DIR}/fdl/*.fdl")
fiddle_sources(fdl_headers "${fdl_files}")
-add_custom_target( fdl_headers DEPENDS ${fdl_headers})
+add_custom_target(fdl_headers DEPENDS ${fdl_headers})
add_custom_command(
OUTPUT ${CMAKE_BINARY_DIR}/main.elf
@@ -87,6 +87,7 @@ add_custom_command(
COMMAND ${CMAKE_C_COMPILER} -nostartfiles -lgcc
-static -L ${CMAKE_BINARY_DIR}/lib -T ${LINKER_SCRIPT}
-o ${CMAKE_BINARY_DIR}/main.elf
+ -Xlinker -Map=${CMAKE_BINARY_DIR}/main.map
-Wl,--no-whole-archive
-Wl,--whole-archive ${CMAKE_BINARY_DIR}/lib/libmain.a
-Wl,--no-whole-archive
diff --git a/fdl/ch573/adc.fdl b/fdl/ch573/adc.fdl
new file mode 100644
index 0000000..bf7fcad
--- /dev/null
+++ b/fdl/ch573/adc.fdl
@@ -0,0 +1,97 @@
+/** Fiddle file for the analog to digital converter. */
+import "ch573/common.fdl";
+
+/** Package for the analog to diginal converter. */
+package ch573.adc {
+ location adc_base = 0x40001000;
+
+ using ch573.common;
+
+ type adc_t : struct {
+ reg (8) @ 0x58 : struct {
+ channel_select : (4);
+ reserved (4);
+ };
+
+ reg cfg(8) @0x59: struct {
+ adc_power_on : enable_t;
+ adc_buf_en : enable_t;
+ adc_diff_en : enable_t;
+
+ ofs_test : enum (1) {
+ [[ c: unqualified ]]
+ OFFSET_TEST_NORMAL = 0,
+ [[ c: unqualified ]]
+ OFFSET_TEST_CALIBRATE = 1,
+ };
+
+ pga_gain : enum (2) {
+ [[ c: unqualified ]]
+ GAIN_DIV_4 = 0,
+ [[ c: unqualified ]]
+ GAIN_DIV_2 = 1,
+ [[ c: unqualified ]]
+ GAIN_NONE = 2,
+ [[ c: unqualified ]]
+ GAIN_MUL_2 = 3,
+ };
+
+ clock_div : enum (2) {
+ [[ c: unqualified ]]
+ CK32M_DIV_10 = 0,
+ [[ c: unqualified ]]
+ CK32M_DIV_4 = 1,
+ [[ c: unqualified ]]
+ CK32M_DIV_6 = 2,
+ [[ c: unqualified ]]
+ CK32M_DIV_8 = 3,
+ };
+ };
+
+ reg convert(8) @0x5A : struct {
+ adc_start : bit_t;
+ reserved(6);
+ eoc_x : bit_t;
+ };
+
+ reg tem_sensor(8) @0x5B : struct {
+ pwr : enable_t;
+ reserved(7);
+ };
+
+ ro reg data(16) @0x5C : struct {
+ ro data_12 : (12);
+ reserved(4);
+ };
+
+ ro reg interrupt_flag(8) @0x5E : struct {
+ reserved(7);
+ ro if_eoc : (1);
+ };
+
+ reg dma_interrupt_control(8) @0x61 : struct {
+ auto_en : enable_t;
+ reserved(2);
+ ie_eoc : enable_t;
+ ie_dma_end : enable_t;
+ dma_loop : enable_t;
+ reserved(1);
+ dma_enable : enable_t;
+ };
+
+ reg dma_interrupt_flag(8) @0x62 : struct {
+ reserved(3);
+ if_dma_end : bit_t;
+ if_end_adc : bit_t;
+ reserved(3);
+ };
+
+ reg auto_cycle(8) @0x63;
+
+ reg dma_now(16) @0x64;
+ reg dma_beg(16) @0x68;
+ reg dma_end(16) @0x6C;
+ };
+
+ instance adc at adc_base : adc_t;
+};
diff --git a/fdl/ch573/gpio.fdl b/fdl/ch573/gpio.fdl
index 86ffaef..e4fbb69 100644
--- a/fdl/ch573/gpio.fdl
+++ b/fdl/ch573/gpio.fdl
@@ -22,15 +22,18 @@ package ch573.gpio {
/** Gpio port type. */
type gpio_port_t : struct {
/** Port direction register. */
- reg (32) : struct {
- dir : enum(1) {
- [[ c: unqualified ]]
- DIR_OUT = 1,
-
- [[ c: unqualified ]]
- DIR_IN = 0,
- } [16];
- reserved(16);
+ union {
+ reg (32) : struct {
+ dir : enum(1) {
+ [[ c: unqualified ]]
+ DIR_OUT = 1,
+
+ [[ c: unqualified ]]
+ DIR_IN = 0,
+ } [16];
+ reserved(16);
+ };
+ reg dir_reg(32);
};
/** Pin input register. */
@@ -49,15 +52,21 @@ package ch573.gpio {
reg clr(32);
/** Pull-up resistor configuration. */
- reg (32) : struct {
- pu : enable_t[16];
- reserved(16);
+ union {
+ reg (32) : struct {
+ pu : enable_t[16];
+ reserved(16);
+ };
+ reg pu_reg(32);
};
/** pull-down/drive configuration register. */
- reg (32) : struct {
- pd_drv : pd_drv_t[16];
- reserved(16);
+ union {
+ reg (32) : struct {
+ pd_drv : pd_drv_t[16];
+ reserved(16);
+ };
+ reg pd_drv_reg(32);
};
};
diff --git a/include/gpio.h b/include/gpio.h
index ab793f1..99b6e5f 100644
--- a/include/gpio.h
+++ b/include/gpio.h
@@ -66,23 +66,25 @@ typedef enum {
typedef void (*gpio_callback_t)(gpio_pin_t pin);
#define On_Gpio(arg) \
- static void __local_on_gpio__(gpio_pin_t pin); \
+ static void __local_on_gpio__(gpio_pin_t pin); \
__attribute__((__section__( \
".gpio_callbacks"))) static volatile gpio_callback_t __gpio__position = \
__local_on_gpio__; \
static void __local_on_gpio__(arg)
+void gpio_init();
+
/** Configure the given gpio pin for .*/
-void configure_gpio(gpio_pin_t pin, gpio_config_t);
+void gpio_configure_pin(gpio_pin_t pin, gpio_config_t);
/** Read the input value of the gpio. */
-int read_gpio(gpio_pin_t pin);
+int gpio_read(gpio_pin_t pin);
/** Sets the gpio pin. */
-void set_gpio(gpio_pin_t pin, int high);
+void gpio_set(gpio_pin_t pin, int high);
/** Set or unset the peripheral to the alternate set of pins. */
-void enable_alternate_funciton(alternate_function_t af, int enable);
+void gpio_enable_alternate_function(alternate_function_t af, int enable);
/** Enables the interrupt for a with the provided interrupt mode. */
-void enable_gpio_interrupt(gpio_pin_t pin, interrupt_mode_t int_mode);
+void gpio_enable_interrupt(gpio_pin_t pin, interrupt_mode_t int_mode);
diff --git a/include/pattern.h b/include/pattern.h
index f5d0a1b..f56e1ec 100644
--- a/include/pattern.h
+++ b/include/pattern.h
@@ -24,3 +24,8 @@ extern pattern_t PATTERNS_END;
#define patterns (&PATTERNS_START)
#define n_patterns (&PATTERNS_END - &PATTERNS_START)
+
+rgb_t twinkle(uint32_t t, size_t x);
+
+rgb_t more_twinkle(uint32_t t, size_t x);
+
diff --git a/include/risc-v.h b/include/risc-v.h
new file mode 100644
index 0000000..946ca7c
--- /dev/null
+++ b/include/risc-v.h
@@ -0,0 +1,45 @@
+#pragma once
+
+#include <stdint.h>
+
+/* Macros and functions for generic RISC-V cores. */
+
+/* Wait for interrupt macro. */
+static inline void wfi()
+{
+ asm volatile("wfi");
+}
+
+/* The mode for the mtvec. */
+typedef enum {
+ MODE_DIRECT = 0,
+ MODE_VECTORED = 1,
+} mtvec_mode_t;
+
+/* Macro to read the value from a RISC-V CSR. */
+#define csrr(csr) \
+ ({ \
+ uint32_t _tmp_csr; \
+ asm volatile("csrr %0, " csr : "=r"(_tmp_csr)); \
+ _tmp_csr; \
+ })
+
+/* Macro to write a value to a RISC-V CSR. */
+#define csrw(csr, v) \
+ { \
+ asm volatile("csrw " csr ", %0" : : "r"(v)); \
+ }
+
+/* Sets the mtvec to point to the given vector_table with the given mode. */
+static inline void set_mtvec(void* vector_table, mtvec_mode_t mode)
+{
+ uint32_t mtvec = (uint32_t)vector_table;
+ mtvec |= !!mode;
+ csrw("mtvec", mtvec);
+}
+
+#define MCAUSE csrr("mcause")
+#define MEPC csrr("mepc")
+#define MTVAL csrr("mtval")
+
+#define __nop() asm volatile ("nop")
diff --git a/include/task.h b/include/task.h
new file mode 100644
index 0000000..63fe543
--- /dev/null
+++ b/include/task.h
@@ -0,0 +1,9 @@
+#pragma once
+
+#include <stdint.h>
+
+typedef struct {
+ uint32_t x[32];
+
+ uint32_t pc;
+} task_t;
diff --git a/include/voltdisc.h b/include/voltdisc.h
new file mode 100644
index 0000000..562b352
--- /dev/null
+++ b/include/voltdisc.h
@@ -0,0 +1,19 @@
+#pragma once
+
+// Volatge discovery. Determines what the voltage of the christmas lights is.
+//
+// This is done by using channel 0 of the ADC (which is on pin PA4). There is a
+// voltage divider from the main power source to pin PA4 which uses a 4.7MOhm
+// resistor and a 470KOhm resistor to divide the voltage by 10, which may then
+// be turned into a reading on the ADC.
+//
+// This helps to determine if the lights being driven are WS2812b's or WS2811 as
+// the latter are run on 12v and use RGB instead of GRB byte order.
+
+
+#include <stdint.h>
+
+typedef uint32_t millivolts_t;
+
+// Returns the estimated input voltage in millivolts.
+millivolts_t get_input_voltage();
diff --git a/include/ws2812b.h b/include/ws2812b.h
index 2061379..6f8aff0 100644
--- a/include/ws2812b.h
+++ b/include/ws2812b.h
@@ -45,11 +45,23 @@ typedef struct {
uint8_t r;
uint8_t g;
uint8_t b;
+
+ /* Color alpha. 0 is perfectly opaque, 255 is perfectly transparent). */
+ uint8_t a;
};
uint32_t color;
};
} rgb_t;
+typedef struct {
+ uint8_t mat[4][4];
+} rgb_mat_t;
+
+/** Returns the new RGB as if rgb1 was overlayed on top of rgb2. */
+rgb_t blend(rgb_t rgb1, rgb_t rgb2);
+
+rgb_t mat_mul(rgb_t rgb, const rgb_mat_t* mat);
+
int write_rgb(struct ws2812b_buf* out, rgb_t color);
void start_dma(struct ws2812b_buf* buf);
diff --git a/src/exc.c b/src/exc.c
index 657ddb8..9b7242b 100644
--- a/src/exc.c
+++ b/src/exc.c
@@ -1,43 +1,50 @@
#include <stdio.h>
+#include "ch573/gpio.h"
#include "isr_vector.h"
#include "panic.h"
-
-#include "ch573/gpio.h"
+#include "risc-v.h"
#define GPIO_PORT_A ch573_gpio__gpio_port_a
#define GPIO_PORT CH573_GPIO__GPIO_PORT_T_INTF
void delay();
-IRQ(exc)
+struct exc_info {
+ uint32_t mtval;
+ uint32_t mepc;
+ uint32_t mcause;
+};
+
+static inline void get_exc_info(struct exc_info* out)
{
- uint32_t mcause, mepc, mtval, *sp;
+ out->mtval = MTVAL;
+ out->mepc = MEPC;
+ out->mcause = MCAUSE;
+}
- asm volatile("csrr %0, mcause" : "=r"(mcause));
- asm volatile("csrr %0, mepc" : "=r"(mepc));
- asm volatile("csrr %0, mtval" : "=r"(mtval));
+IRQ(exc)
+{
+ struct exc_info ei;
+ get_exc_info(&ei);
printf("Hardware Exception Caught:\n");
- printf(" mcause: 0x%08x\n", mcause);
- printf(" mepc: 0x%08x\n", mepc);
- printf(" mtval: 0x%08x\n", mtval);
+ printf(" mcause: 0x%08x\n", ei.mcause);
+ printf(" mepc: 0x%08x\n", ei.mepc);
+ printf(" mtval: 0x%08x\n", ei.mtval);
- panic(mcause);
+ panic(ei.mcause);
}
IRQ(nmi)
{
- uint32_t mcause, mepc, mtval, *sp;
-
- asm volatile("csrr %0, mcause" : "=r"(mcause));
- asm volatile("csrr %0, mepc" : "=r"(mepc));
- asm volatile("csrr %0, mtval" : "=r"(mtval));
+ struct exc_info ei;
+ get_exc_info(&ei);
printf("Unhandled NMI Caught:\n");
- printf(" mcause: 0x%08x\n", mcause);
- printf(" mepc: 0x%08x\n", mepc);
- printf(" mtval: 0x%08x\n", mtval);
+ printf(" mcause: 0x%08x\n", ei.mcause);
+ printf(" mepc: 0x%08x\n", ei.mepc);
+ printf(" mtval: 0x%08x\n", ei.mtval);
- panic(mcause);
+ panic(ei.mcause);
}
diff --git a/src/gpio.c b/src/gpio.c
index e016179..b093b94 100644
--- a/src/gpio.c
+++ b/src/gpio.c
@@ -3,7 +3,24 @@
#include "ch573/pfic.h"
#include "isr_vector.h"
-void configure_gpio(gpio_pin_t pin, gpio_config_t cfg)
+/* Sets all the GPIO pins to INPUT_PULL_UP configuration. This is to reduce
+ * electrical noise in the system. */
+void gpio_init()
+{
+ // Set GPIO's to input.
+ GPIO_PORT.dir_reg.set(GPIO_PORT_A, 0x0);
+ GPIO_PORT.dir_reg.set(GPIO_PORT_B, 0x0);
+
+ // Turn off all the pull-down resistors.
+ GPIO_PORT.pd_drv_reg.set(GPIO_PORT_A, 0x0);
+ GPIO_PORT.pd_drv_reg.set(GPIO_PORT_B, 0x0);
+
+ // Turn on the pull up resistors.
+ GPIO_PORT.pu_reg.set(GPIO_PORT_A, 0xffffffff);
+ GPIO_PORT.pu_reg.set(GPIO_PORT_B, 0xffffffff);
+}
+
+void gpio_configure_pin(gpio_pin_t pin, gpio_config_t cfg)
{
int ipin = pin;
struct ch573_gpio__gpio_port_t* port;
@@ -43,7 +60,7 @@ void configure_gpio(gpio_pin_t pin, gpio_config_t cfg)
}
}
-int read_gpio(gpio_pin_t pin)
+int gpio_read(gpio_pin_t pin)
{
int ipin = pin;
struct ch573_gpio__gpio_port_t* port;
@@ -57,7 +74,7 @@ int read_gpio(gpio_pin_t pin)
return !!GPIO_PORT.pin.in.get(port, ipin);
}
-void set_gpio(gpio_pin_t pin, int high)
+void gpio_set(gpio_pin_t pin, int high)
{
int ipin = pin;
struct ch573_gpio__gpio_port_t* port;
@@ -71,9 +88,13 @@ void set_gpio(gpio_pin_t pin, int high)
GPIO_PORT.out.set(port, !!high, ipin);
}
-void enable_alternate_function(alternate_function_t afn)
+void gpio_enable_alternate_function(alternate_function_t afn, int enable)
{
- GPIO_I.pin_alternate.set(GPIO, 1 << afn);
+ if (enable) {
+ GPIO_I.pin_alternate.set(GPIO, 1 << afn);
+ } else {
+ GPIO->pin_alternate &= ~(1 << afn);
+ };
}
#define PFIC ch573_pfic__pfic
@@ -83,7 +104,7 @@ static void enable_gpio_pfic(int irq)
PFIC->interrupt_enable |= irq;
}
-void enable_gpio_interrupt(gpio_pin_t pin, interrupt_mode_t int_mode)
+void gpio_enable_interrupt(gpio_pin_t pin, interrupt_mode_t int_mode)
{
int ipin = pin;
struct ch573_gpio__gpio_port_t* port;
@@ -150,7 +171,7 @@ void fire_irq(volatile uint16_t* int_flag_ptr, int is_port_b)
for (cur = &GPIO_LISTENERS_START; cur < &GPIO_LISTENERS_END; ++cur) {
(*cur)(pin | is_port_b);
}
- *int_flag_ptr |= 1 << pin; // Clear the interrupt for this pin.
+ *int_flag_ptr |= 1 << pin; // Clear the interrupt for this pin.
}
}
diff --git a/src/init.c b/src/init.c
index 3aacc66..5f276cb 100644
--- a/src/init.c
+++ b/src/init.c
@@ -1,11 +1,11 @@
#include <stddef.h>
#include <stdint.h>
-#include <stdio.h>
#include "ch573/systick.h"
-#include "clock.h"
+#include "gpio.h"
#include "io.h"
#include "isr_vector.h"
+#include "risc-v.h"
void on_reset(void);
@@ -67,13 +67,6 @@ extern uint32_t DATA_SEGMENT_STOP;
extern uint32_t BSS_START;
extern uint32_t BSS_STOP;
-static inline void set_mtvec(void* vector_table)
-{
- uint32_t mtvec = (uint32_t)vector_table;
- mtvec |= 1; // Set interrupt table mode to "VECTORED"
- asm volatile("csrw mtvec, %0" : : "r"(mtvec));
-}
-
/*
* Initialize the data segment and the bss segment.
*
@@ -115,9 +108,12 @@ static __attribute((__section__(".sinit.1"))) void start(void)
/* Initialize the data segments. */
init_data_segments();
/* Set the mtvec to the isr_vector. */
- set_mtvec(&isr_vector);
+ set_mtvec(&isr_vector, MODE_VECTORED);
enable_interrupts();
+ /* Initialize GPIO pins so they don't create unnecessary electrical noise. */
+ gpio_init();
+
/* Initialize stdout. */
init_uart1_for_stdout();
diff --git a/src/ir.c b/src/ir.c
new file mode 100644
index 0000000..46ca2bd
--- /dev/null
+++ b/src/ir.c
@@ -0,0 +1,9 @@
+#include "ch573/gpio.h"
+
+#define GPIO_PORT_A ch573_gpio__gpio_port_a
+#define GPIO_PORT_B ch573_gpio__gpio_port_b
+#define GPIO_PORT CH573_GPIO__GPIO_PORT_T_INTF
+#define GPIO_I CH573_GPIO__GPIO_T_INTF
+#define GPIO ch573_gpio__gpio
+
+
diff --git a/src/main.c b/src/main.c
index 525db53..6a536d1 100644
--- a/src/main.c
+++ b/src/main.c
@@ -4,21 +4,24 @@
#include "btsel.h"
#include "byte_math.h"
+#include "ch573/adc.h"
#include "ch573/gpio.h"
#include "ch573/pfic.h"
#include "ch573/pwr.h"
#include "ch573/uart.h"
#include "clock.h"
+#include "gpio.h"
#include "isr_vector.h"
#include "panic.h"
#include "pattern.h"
+#include "risc-v.h"
#include "spi.h"
#include "string.h"
#include "sysled.h"
#include "system.h"
#include "systick.h"
+#include "voltdisc.h"
#include "ws2812b.h"
-#include "gpio.h"
#ifndef LED_BYTE_ORDER
#define LED_BYTE_ORDER GRB
@@ -43,6 +46,9 @@
#define GPIO_I CH573_GPIO__GPIO_T_INTF
#define GPIO ch573_gpio__gpio
+#define ADC_I CH573_ADC__ADC_T_INTF
+#define ADC ch573_adc__adc
+
#define UART1 ch573_uart__uart1
#define UART CH573_UART__UART_T_INTF
@@ -126,11 +132,20 @@ int main(void)
enable_sysled();
enable_spi();
+ gpio_configure_pin(PIN_PB7, PIN_CFG_INPUT_PULL_UP);
+ gpio_enable_interrupt(PIN_PB7, INT_MODE_FALLING_EDGE);
+
+ const char* pattern_name;
+ if (gpio_read(PIN_PB7) == 0) {
+ // Holding pin PB7 during restart will set the default pattern to a
+ // different one.
+ pattern_name = "Warm Twinkle";
+ } else {
+ pattern_name = TOSTRING(DEFAULT_PATTERN);
+ }
for (current_pattern_idx = 0; current_pattern_idx < n_patterns;
++current_pattern_idx) {
- if (strcmp(
- patterns[current_pattern_idx].name, "" TOSTRING(DEFAULT_PATTERN)) ==
- 0) {
+ if (strcmp(patterns[current_pattern_idx].name, pattern_name) == 0) {
break;
}
}
@@ -144,20 +159,24 @@ int main(void)
printf("\nRunning Pattern '%s'\n", patterns[current_pattern_idx].name);
- configure_gpio(PIN_PB7, PIN_CFG_INPUT_PULL_UP);
- enable_gpio_interrupt(PIN_PB7, INT_MODE_FALLING_EDGE);
- // enable_bootsel_button();
-
size_t n = sizeof(buf);
struct ws2812b_buf ws_buf;
make_wsb2812b(&ws_buf, buf, n);
- ws_buf.byte_order = LED_BYTE_ORDER_ENUM;
-
- rgb_t color;
- GPIO_PORT.dir.set(GPIO_PORT_A, DIR_OUT, 10);
+ millivolts_t voltage = get_input_voltage();
+ printf("Measured input voltage at %u mV\n", voltage);
+
+ if (voltage > 7000) {
+ // Assuming byte order RGB
+ ws_buf.byte_order = BYTE_ORDER_RGB;
+ printf("Using RGB byte order.\n");
+ } else {
+ // Assuming byte order GRB
+ ws_buf.byte_order = BYTE_ORDER_GRB;
+ printf("Using GRB byte order.\n");
+ }
- // GPIO->pb_interrupt_mode |= (1 << 7) | (1 << 8);
+ gpio_configure_pin(PIN_PA10, PIN_CFG_OUTPUT_5mA);
while (1) {
pattern_t* current_pattern = &patterns[current_pattern_idx];
@@ -168,12 +187,11 @@ int main(void)
}
while (spin_lock) {
- // set_sysled(1); // Setting the sysled helps me to measure down time.
- GPIO_PORT.out.set(GPIO_PORT_A, ON, 10);
+ gpio_set(PIN_PA10, ON);
+ wfi();
}
- GPIO_PORT.out.set(GPIO_PORT_A, OFF, 10);
-
spin_lock = 1;
+ gpio_set(PIN_PA10, OFF);
for (int j = 0; j < N_DMA_XFER; ++j) {
wait_for_dma();
diff --git a/src/patterns/candycane.c b/src/patterns/candycane.c
index dbf80de..42a9ad7 100644
--- a/src/patterns/candycane.c
+++ b/src/patterns/candycane.c
@@ -1,23 +1,49 @@
#include "byte_math.h"
#include "pattern.h"
-static rgb_t get_rgb(uint32_t time, size_t x)
+static rgb_t white(uint32_t time, size_t x)
+{
+ int w = calc_w((time & 0xff) + x * 4);
+ rgb_t color;
+ color.color = 0x00ffffff;
+ color.a = 255 - w;
+ return color;
+}
+
+static rgb_t candycane_bg(uint32_t time, size_t x)
{
int r = 0, g = 0, b = 0;
uint8_t time8 = time & 0xff;
- int w = calc_w(time8 + x * 4);
r = 0xff;
g = byte_scale(byte_sin(time8 + x * 2), 0x90);
b = byte_scale(byte_sin(time8 + x * 2), 0x20);
- rgb_t color;
- color.color = 0;
- color.r = clip(r + w);
- color.g = clip(byte_scale(g, AS_BYTE(0.75)) + w);
- color.b = clip(byte_scale(b, AS_BYTE(0.75)) + w);
- return color;
+ rgb_t bg;
+ bg.color = 0;
+ bg.r = r;
+ bg.g = byte_scale(g, AS_BYTE(0.75));
+ bg.b = byte_scale(b, AS_BYTE(0.75));
+
+ return blend(white(time, x), bg);
+}
+
+static rgb_t candycane_twinkle(uint32_t time, size_t x)
+{
+ rgb_t twink = more_twinkle(time / 4, x);
+ int a = twink.a;
+
+ if (time & 0x3) {
+ // Linear interpolate.
+ int amt = time % 4;
+ a = (a * (4 - amt) + more_twinkle((time / 4) + 1, x).a * amt) / 4;
+ }
+
+ rgb_t bg = candycane_bg(time, x);
+
+ bg.a = a;
+ return bg;
}
static void reset(void)
@@ -25,4 +51,13 @@ static void reset(void)
}
__attribute__((__section__(".patterns"))) volatile static pattern_t pat =
- ((pattern_t){.get_rgb = get_rgb, .name = "CandyCane", .reset = reset});
+ ((pattern_t){.get_rgb = candycane_bg, .name = "CandyCane", .reset = reset});
+
+__attribute__((__section__(".patterns"))) volatile static pattern_t naked_pat =
+ ((pattern_t){.get_rgb = white, .name = "Naked White", .reset = reset});
+
+__attribute__((
+ __section__(".patterns"))) volatile static pattern_t candycane_twinkle_pat =
+ ((pattern_t){.get_rgb = candycane_twinkle,
+ .name = "Candycane Twinkle",
+ .reset = reset});
diff --git a/src/patterns/twinkle.c b/src/patterns/twinkle.c
index 564a30a..0c3f985 100644
--- a/src/patterns/twinkle.c
+++ b/src/patterns/twinkle.c
@@ -1,54 +1,144 @@
#include <stdio.h>
+
#include "byte_math.h"
#include "pattern.h"
-static uint8_t pseudo_random(uint8_t x) {
- return (1103515245 * x + 12345) & 0xFF; // & 0xFF ensures the result is 0-255
+static uint8_t pseudo_random(uint8_t x)
+{
+ return (1103515245 * x + 12345) & 0xFF; // & 0xFF ensures the result is 0-255
+}
+
+rgb_t twinkle(uint32_t time, size_t x)
+{
+ uint8_t time_offset = pseudo_random(x);
+
+ uint32_t adj_time = time - time_offset;
+ uint32_t time8 = adj_time & 0xff;
+ uint32_t speed = pseudo_random((adj_time >> 8) + x) & 0x3;
+
+ time8 *= speed;
+ uint8_t w = 0;
+ if (time8 <= 255) {
+ w = calc_w(time8);
+ } else {
+ w = 0;
+ }
+
+ rgb_t r;
+ r.r = 0xff;
+ r.g = 0xff;
+ r.b = 0xff;
+ r.a = 0xff - w;
+ return r;
}
+rgb_t more_twinkle(uint32_t time, size_t x)
+{
+ uint8_t time_offset = pseudo_random(x);
+
+#define N 91
+
+ uint32_t adj_time = time - time_offset;
+ uint32_t time8 = adj_time % N;
+ uint32_t speed = pseudo_random((adj_time / N) + x) % 3;
+
+ time8 *= speed;
+ time8 += (255 - N);
+ uint8_t w = 0;
+ if (time8 <= 255) {
+ w = calc_w(time8);
+ } else {
+ w = 0;
+ }
+
+ rgb_t r;
+ r.r = 0xff;
+ r.g = 0xff;
+ r.b = 0xff;
+ r.a = 0xff - w;
+ return r;
+}
static rgb_t get_rgb(uint32_t time, size_t x)
{
- int r = 0, g = 0, b = 0;
+ uint8_t time8 = time & 0xff;
+
+ rgb_t twink = twinkle(time, x);
+ rgb_t bg;
+ bg.color = 0;
+ bg.r = 0xff;
+ bg.g = byte_scale(byte_sin(time8 + x * 2), 0x60);
+ bg.b = 0;
+ bg.a = 0xa0;
+
+ return blend(twink, bg);
+}
+
+static rgb_t blue_twinkle(uint32_t time, size_t x)
+{
+ rgb_t bg;
uint8_t time8 = time & 0xff;
- uint8_t time_offset = pseudo_random(x);
- uint32_t adjusted_time = time - time_offset;
+ bg.color = 0;
+ bg.r = byte_sin((time8 * 2 + x * 2 + 0x80) * 2);
+ bg.g = byte_sin(time8 + x * 2);
+ bg.b = 0xff;
+ bg.a = 0xc0;
- // The random number for this "metaframe." The metaframe is enough to show 1
- // flash. It's used to keep the same LED's from consistently repeating.
- uint32_t metaframe = adjusted_time >> 8;
- uint8_t rand = pseudo_random(x + metaframe);
- uint8_t speed = pseudo_random(rand) % 16;
- uint8_t off = pseudo_random(rand + speed);
+ return blend(twinkle(time, x), bg);
+}
- if (speed > 4) {
- speed = 0;
- }
+static rgb_t warm_twinkle(uint32_t time, size_t x)
+{
+ uint8_t time8 = time & 0xff;
- uint32_t w_index = ((adjusted_time - off) * speed) & 0xff;
- int w = 0;
- if (w_index < 255) {
- w = calc_w(w_index);
- }
+ rgb_t twink = twinkle(time, x);
+ rgb_t bg;
+ bg.color = 0;
+ bg.r = 0xff;
+ bg.g = byte_scale(byte_sin(time8 + x * 2), 0x60);
+ bg.b = 0;
+ bg.a = twink.a;
- r = 0xff;
- g = byte_scale(byte_sin(time8 + x * 2), 0x60);
- b = 0;
+ return bg;
+}
+
+static rgb_t cool_twinkle(uint32_t time, size_t x)
+{
+ rgb_t bg;
+ uint8_t time8 = time & 0xff;
+ rgb_t twink = twinkle(time, x);
+
+ bg.color = 0;
+ bg.r = byte_sin((time8 * 2 + x * 2 + 0x80) * 2);
+ bg.g = byte_sin(time8 + x * 2);
+ bg.b = 0xff;
+ bg.a = twink.a;
- rgb_t color;
- color.color = 0;
- color.r = clip(r + w);
- color.g = clip(byte_scale(g, AS_BYTE(0.75)) + w);
- color.b = clip(byte_scale(b, AS_BYTE(0.75)) + w);
- return color;
+ return bg;
}
static void reset(void)
{
}
-__attribute__((__section__(".patterns"))) volatile static pattern_t pat =
+__attribute__((__section__(".patterns"))) volatile static pattern_t p08_pat =
((pattern_t){.get_rgb = get_rgb, .name = "Twinkle", .reset = reset});
+
+__attribute__((
+ __section__(".patterns"))) volatile static pattern_t p09_naked_pat =
+ ((pattern_t){.get_rgb = twinkle, .name = "Naked Twinkle", .reset = reset});
+
+__attribute__((__section__(
+ ".patterns"))) volatile static pattern_t p10_naked_pat = ((pattern_t){
+ .get_rgb = warm_twinkle, .name = "Warm Twinkle", .reset = reset});
+
+__attribute__((__section__(".patterns"))) volatile static pattern_t p11_cool_pat =
+ ((pattern_t){
+ .get_rgb = cool_twinkle, .name = "Cool Twinkle", .reset = reset});
+
+__attribute__((__section__(".patterns"))) volatile static pattern_t blue_pat =
+ ((pattern_t){
+ .get_rgb = blue_twinkle, .name = "Blue Twinkle", .reset = reset});
diff --git a/src/spi.c b/src/spi.c
index a416014..d19b2bb 100644
--- a/src/spi.c
+++ b/src/spi.c
@@ -4,6 +4,7 @@
#include "ch573/gpio.h"
#include "ch573/spi.h"
+#include "gpio.h"
#include "sysled.h"
#define MAX_SPI_FIFO 8
@@ -17,57 +18,29 @@
void enable_spi(void)
{
- GPIO_I.pin_alternate.pin_spi0.set(GPIO, ON);
+ gpio_enable_alternate_function(AF_SPI, 1);
+ gpio_configure_pin(PIN_PB14, PIN_CFG_OUTPUT_20mA);
+ gpio_configure_pin(PIN_PB12, PIN_CFG_OUTPUT_20mA);
- GPIO_PORT.out.set(GPIO_PORT_A, ON, 12);
- GPIO_PORT.dir.set(GPIO_PORT_A, DIR_OUT, 12);
- GPIO_PORT.dir.set(GPIO_PORT_A, DIR_OUT, 14);
- GPIO_PORT.pd_drv.set(GPIO_PORT_A, 0, 12);
- GPIO_PORT.pd_drv.set(GPIO_PORT_A, 0, 14);
+ gpio_configure_pin(PIN_PB15, PIN_CFG_INPUT_PULL_DOWN);
- GPIO_PORT.dir.set(GPIO_PORT_B, DIR_OUT, 12);
- GPIO_PORT.dir.set(GPIO_PORT_B, DIR_OUT, 14);
- GPIO_PORT.pd_drv.set(GPIO_PORT_B, 0, 12);
- GPIO_PORT.pd_drv.set(GPIO_PORT_B, 0, 14);
- GPIO_PORT.out.set(GPIO_PORT_B, OFF, 14);
- GPIO_PORT.out.set(GPIO_PORT_B, ON, 12);
+ gpio_configure_pin(PIN_PA14, PIN_CFG_OUTPUT_20mA);
+ gpio_configure_pin(PIN_PA12, PIN_CFG_OUTPUT_20mA);
- GPIO_PORT.pu.set(GPIO_PORT_B, ENABLED, 14);
-
- GPIO_PORT.dir.set(GPIO_PORT_B, DIR_IN, 13);
- GPIO_PORT.dir.set(GPIO_PORT_B, DIR_IN, 15);
- GPIO_PORT.dir.set(GPIO_PORT_A, DIR_IN, 13);
- GPIO_PORT.dir.set(GPIO_PORT_A, DIR_IN, 15);
+ gpio_configure_pin(PIN_PA15, PIN_CFG_INPUT_PULL_DOWN);
SPI.clock_div.set(SPI0, 25);
SPI.ctrl_mod.all_clear.set(SPI0, 1);
- // SPI.ctrl_mod.set(SPI0, 0xe0); // Set mosi and sck
SPI.ctrl_mod.all_clear.set(SPI0, 0);
- SPI.ctrl_mod.pin_enable.set(SPI0, 0x2); // Set mosi and sck
+ SPI.ctrl_mod.pin_enable.set(SPI0, 0x7); // Set mosi and sck
SPI.ctrl_cfg.auto_if.set(SPI0, 1);
SPI.ctrl_cfg.dma_enable.set(SPI0, OFF);
+ SPI.ctrl_mod.mst_sck_mod.set(SPI0, 0);
}
-// void write_color(uint8_t r, uint8_t g, uint8_t b)
-// {
-//
-//
-// while (!SPI.int_flag.if_fifo_hf.get(SPI0));
-// SPI.fifo.set(SPI0, r);
-// SPI.fifo.set(SPI0, g);
-// SPI.fifo.set(SPI0, b);
-// }
-
void dma_transfer(void* output_buffer, size_t len)
{
- // Clear everything.
- // SPI.ctrl_mod.all_clear.set(SPI0, 1);
- // SPI.ctrl_mod.all_clear.set(SPI0, 0);
- // SPI.ctrl_cfg.dma_enable.set(SPI0, OFF);
-
- // printf("Start DMA: %p, %zu\n", output_buffer, len);
-
SPI.ctrl_mod.fifo_dir.set(SPI0, FIFO_DIR_OUTPUT);
SPI.dma_beg.set(SPI0, (uint32_t)output_buffer);
SPI.dma_end.set(SPI0, (uint32_t)(output_buffer + len));
@@ -85,17 +58,3 @@ void wait_for_dma()
}
set_sysled(0);
}
-
-void run_spi(void)
-{
- GPIO_PORT.out.set(GPIO_PORT_A, ON, 12);
- while (1) {
- SPI.total_count.set(SPI0, 1024);
- // GPIO_PORT_A->clr |= 1 << 12;
-
- while (SPI.fifo_count.get(SPI0) == 8);
-
- SPI.fifo.set(SPI0, 0xaa);
- SPI.total_count.set(SPI0, 1024);
- }
-}
diff --git a/src/voltdisc.c b/src/voltdisc.c
new file mode 100644
index 0000000..034fdf8
--- /dev/null
+++ b/src/voltdisc.c
@@ -0,0 +1,44 @@
+#include "voltdisc.h"
+
+#include "ch573/adc.h"
+#include "gpio.h"
+#include "risc-v.h"
+
+#define ADC_I CH573_ADC__ADC_T_INTF
+#define ADC ch573_adc__adc
+
+#define VOLTAGE_DIVIDER_COEF (11)
+
+millivolts_t get_input_voltage()
+{
+ // Pull down the voltage of the pin. Do this in case the MCU is in a chassis
+ // which does not have the voltage divider.
+ gpio_configure_pin(PIN_PA4, PIN_CFG_INPUT_PULL_DOWN);
+
+ // Wait for the pin to discharge.
+ for (int i = 0; i < 10; ++i) {
+ __nop();
+ }
+
+ // Configure the pin to "floating".
+ gpio_configure_pin(PIN_PA4, PIN_CFG_INPUT_FLOATING);
+
+ // Configure the ADC for reading.
+ ADC_I.cfg.adc_buf_en.set(ADC, ENABLED);
+ ADC_I.cfg.adc_power_on.set(ADC, ENABLED);
+ ADC_I.channel_select.set(ADC, 0);
+ ADC_I.dma_interrupt_control.auto_en.set(ADC, 1);
+ ADC_I.convert.adc_start.set(ADC, ON);
+
+ uint32_t raw_value;
+ // Wait until the ADC is ready for reading.
+ while (!ADC_I.interrupt_flag.if_eoc.get(ADC));
+ raw_value = ADC_I.data.get(ADC);
+
+ ADC_I.convert.adc_start.set(ADC, OFF);
+ ADC_I.cfg.adc_power_on.set(ADC, DISABLED);
+
+ // Attempt to calculate the original voltage
+ return (millivolts_t)(raw_value * 1.05 / 2048.0 * 1000) *
+ VOLTAGE_DIVIDER_COEF;
+}
diff --git a/src/ws2812b.c b/src/ws2812b.c
index 1dea9f1..692e8ad 100644
--- a/src/ws2812b.c
+++ b/src/ws2812b.c
@@ -2,6 +2,7 @@
#include <string.h>
+#include "byte_math.h"
#include "spi.h"
#include "sysled.h"
@@ -38,9 +39,9 @@ inline static void complie_color_inline(
color.g = tmp;
}
- color.r = color.r;
- color.g = color.g;
- color.b = color.b;
+ color.r = byte_scale(color.r, 255 - color.a);
+ color.g = byte_scale(color.g, 255 - color.a);
+ color.b = byte_scale(color.b, 255 - color.a);
out->first_bits =
BYTE_1(COLOR_BYTE_1(color.r)) | BYTE_2(COLOR_BYTE_2(color.r)) |
@@ -79,7 +80,8 @@ int write_rgb(struct ws2812b_buf* out, rgb_t color)
while ((dma_loc - CLIP_TO_DMA_BITS(out->buf + out->cur) <
TOTAL_BYTES_PER_LED) &&
(dma_loc < dma_end)) {
- set_sysled(1); // Little indication to tell if we are waiting for the DMA.
+ set_sysled(
+ 1); // Little indication to tell if we are waiting for the DMA.
dma_loc = *dma_now;
}
set_sysled(0);
@@ -120,3 +122,45 @@ void compiled_color_dbg_str(struct rgb_compiled* c, char* out)
}
*(out++) = 0;
}
+
+rgb_t blend(rgb_t c1, rgb_t c2)
+{
+ rgb_t r;
+
+ uint8_t prop = 255 - c1.a;
+ uint8_t rprop = 255 - prop;
+
+ r.r = clip((int)byte_scale(c1.r, prop) + byte_scale(c2.r, rprop));
+ r.g = clip((int)byte_scale(c1.g, prop) + byte_scale(c2.g, rprop));
+ r.b = clip((int)byte_scale(c1.b, prop) + byte_scale(c2.b, rprop));
+ r.a = 255 - (prop + byte_scale(255 - c2.a, rprop));
+
+ return r;
+}
+
+rgb_t mat_mul(rgb_t rgb, const rgb_mat_t* mat)
+{
+ rgb_t ret;
+
+ ret.r = byte_scale(rgb.r, mat->mat[0][0]) +
+ byte_scale(rgb.g, mat->mat[0][1]) +
+ byte_scale(rgb.b, mat->mat[0][2]) +
+ byte_scale(rgb.a, mat->mat[0][3]);
+
+ ret.g = byte_scale(rgb.r, mat->mat[1][0]) +
+ byte_scale(rgb.g, mat->mat[1][1]) +
+ byte_scale(rgb.b, mat->mat[1][2]) +
+ byte_scale(rgb.a, mat->mat[1][3]);
+
+ ret.b = byte_scale(rgb.r, mat->mat[2][0]) +
+ byte_scale(rgb.g, mat->mat[2][1]) +
+ byte_scale(rgb.b, mat->mat[2][2]) +
+ byte_scale(rgb.a, mat->mat[2][3]);
+
+ ret.a = byte_scale(rgb.r, mat->mat[3][0]) +
+ byte_scale(rgb.g, mat->mat[3][1]) +
+ byte_scale(rgb.b, mat->mat[3][2]) +
+ byte_scale(rgb.a, mat->mat[3][3]);
+
+ return ret;
+}
diff --git a/stubs/libgloss.a b/stubs/libgloss.a
new file mode 100644
index 0000000..2aa2112
--- /dev/null
+++ b/stubs/libgloss.a
Binary files differ