Compare commits
29 commits
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
f83bac7e42 | ||
|
|
9c45cfb0e4 | ||
|
|
3614319ecd | ||
|
|
dbd84325c7 | ||
|
|
c8ad602b45 | ||
|
|
1037d3f080 | ||
|
|
d55e3bf833 | ||
|
|
0bd9873153 | ||
|
|
2156ca0407 | ||
|
|
fb9903f97d | ||
|
|
282920f9ce | ||
|
|
267d78d6cf | ||
|
|
386371d8fd | ||
|
|
ca4f8764be | ||
| cffac25915 | |||
| 7155be1a75 | |||
| e4506e5a57 | |||
|
|
eadf2ee814 | ||
|
|
d87532b044 | ||
|
|
68943a8fcd | ||
|
|
5ad5f33a16 | ||
|
|
429d625ba7 | ||
|
|
98a2da6da4 | ||
|
|
b0e9d045f8 | ||
|
|
40d0971635 | ||
|
|
1faaec39b3 | ||
|
|
67ac7d48d4 | ||
|
|
a6dec45c38 | ||
|
|
4430d1ceb5 |
16 changed files with 328 additions and 273 deletions
6
.github/workflows/githubci.yml
vendored
6
.github/workflows/githubci.yml
vendored
|
|
@ -12,11 +12,11 @@ jobs:
|
|||
runs-on: ubuntu-latest
|
||||
|
||||
steps:
|
||||
- uses: actions/setup-python@v1
|
||||
- uses: actions/setup-python@v5
|
||||
with:
|
||||
python-version: '3.8'
|
||||
- uses: actions/checkout@v2
|
||||
- uses: actions/checkout@v2
|
||||
- uses: actions/checkout@v4
|
||||
- uses: actions/checkout@v4
|
||||
with:
|
||||
repository: adafruit/ci-arduino
|
||||
path: ci
|
||||
|
|
|
|||
|
|
@ -38,6 +38,13 @@ supported boards. Notes have been moved to the bottom of the code.
|
|||
uint8_t clockPin = 13;
|
||||
uint8_t latchPin = 0;
|
||||
uint8_t oePin = 1;
|
||||
#elif defined(ARDUINO_ADAFRUIT_FEATHER_ESP32C6) // Feather ESP32-C6
|
||||
// not featherwing compatible, but can 'hand wire' if desired
|
||||
uint8_t rgbPins[] = {6, A3, A1, A0, A2, 0};
|
||||
uint8_t addrPins[] = {8, 5, 15, 7};
|
||||
uint8_t clockPin = 14;
|
||||
uint8_t latchPin = RX;
|
||||
uint8_t oePin = TX;
|
||||
#elif defined(ARDUINO_ADAFRUIT_FEATHER_ESP32S2) // Feather ESP32-S2
|
||||
// M0/M4/RP2040 Matrix FeatherWing compatible:
|
||||
uint8_t rgbPins[] = {6, 5, 9, 11, 10, 12};
|
||||
|
|
@ -59,11 +66,11 @@ supported boards. Notes have been moved to the bottom of the code.
|
|||
uint8_t latchPin = 0;
|
||||
uint8_t oePin = 1;
|
||||
#elif defined(_SAMD21_) // Feather M0 variants
|
||||
uint8_t rgbPins[] = {6, 7, 10, 11, 12, 13};
|
||||
uint8_t addrPins[] = {0, 1, 2, 3};
|
||||
uint8_t clockPin = SDA;
|
||||
uint8_t latchPin = 4;
|
||||
uint8_t oePin = 5;
|
||||
uint8_t rgbPins[] = {6, 5, 9, 11, 10, 12};
|
||||
uint8_t addrPins[] = {A5, A4, A3, A2};
|
||||
uint8_t clockPin = 13;
|
||||
uint8_t latchPin = 0;
|
||||
uint8_t oePin = 1;
|
||||
#elif defined(NRF52_SERIES) // Special nRF52840 FeatherWing pinout
|
||||
uint8_t rgbPins[] = {6, A5, A1, A0, A4, 11};
|
||||
uint8_t addrPins[] = {10, 5, 13, 9};
|
||||
|
|
|
|||
|
|
@ -1,5 +1,5 @@
|
|||
name=Adafruit Protomatter
|
||||
version=1.6.1
|
||||
version=1.7.0
|
||||
author=Adafruit
|
||||
maintainer=Adafruit <info@adafruit.com>
|
||||
sentence=A library for Adafruit RGB LED matrices.
|
||||
|
|
|
|||
|
|
@ -192,6 +192,7 @@ _PM_CUSTOM_BLAST If defined, instructs core code to not compile
|
|||
#include "esp32-s2.h"
|
||||
#include "esp32-s3.h"
|
||||
#include "esp32-c3.h"
|
||||
#include "esp32-c6.h"
|
||||
#include "nrf52.h"
|
||||
#include "rp2040.h"
|
||||
#include "samd-common.h"
|
||||
|
|
|
|||
|
|
@ -29,7 +29,7 @@
|
|||
#define _PM_portSetRegister(pin) (volatile uint32_t *)&GPIO.out_w1ts
|
||||
#define _PM_portClearRegister(pin) (volatile uint32_t *)&GPIO.out_w1tc
|
||||
|
||||
#define _PM_portBitMask(pin) (1U << ((pin)&31))
|
||||
#define _PM_portBitMask(pin) (1U << ((pin) & 31))
|
||||
|
||||
#if __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
|
||||
#define _PM_byteOffset(pin) ((pin & 31) / 8)
|
||||
|
|
|
|||
57
src/arch/esp32-c6.h
Normal file
57
src/arch/esp32-c6.h
Normal file
|
|
@ -0,0 +1,57 @@
|
|||
/*!
|
||||
* @file esp32-c3.h
|
||||
*
|
||||
* Part of Adafruit's Protomatter library for HUB75-style RGB LED matrices.
|
||||
* This file contains ESP32-C3-SPECIFIC CODE.
|
||||
*
|
||||
* Adafruit invests time and resources providing this open source code,
|
||||
* please support Adafruit and open-source hardware by purchasing
|
||||
* products from Adafruit!
|
||||
*
|
||||
* Written by Phil "Paint Your Dragon" Burgess and Jeff Epler for
|
||||
* Adafruit Industries, with contributions from the open source community.
|
||||
*
|
||||
* BSD license, all text here must be included in any redistribution.
|
||||
*
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
// NOTE: there is some intentional repetition in the macros and functions
|
||||
// for some ESP32 variants. Previously they were all one file, but complex
|
||||
// preprocessor directives were turning into spaghetti. THEREFORE, if making
|
||||
// a change or bugfix in one variant-specific header, check the others to
|
||||
// see if the same should be applied!
|
||||
|
||||
#if defined(CONFIG_IDF_TARGET_ESP32C6)
|
||||
|
||||
#define _PM_portOutRegister(pin) (volatile uint32_t *)&GPIO.out
|
||||
#define _PM_portSetRegister(pin) (volatile uint32_t *)&GPIO.out_w1ts
|
||||
#define _PM_portClearRegister(pin) (volatile uint32_t *)&GPIO.out_w1tc
|
||||
|
||||
#define _PM_portBitMask(pin) (1U << ((pin) & 31))
|
||||
|
||||
#if __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
|
||||
#define _PM_byteOffset(pin) ((pin & 31) / 8)
|
||||
#define _PM_wordOffset(pin) ((pin & 31) / 16)
|
||||
#else
|
||||
#define _PM_byteOffset(pin) (3 - ((pin & 31) / 8))
|
||||
#define _PM_wordOffset(pin) (1 - ((pin & 31) / 16))
|
||||
#endif
|
||||
|
||||
// No special peripheral setup on ESP32C3, just use common timer init...
|
||||
#define _PM_timerInit(core) _PM_esp32commonTimerInit(core);
|
||||
|
||||
#if defined(ARDUINO) // COMPILING FOR ARDUINO ------------------------------
|
||||
// Return current count value (timer enabled or not).
|
||||
// Timer must be previously initialized.
|
||||
// This function is the same on all ESP32 parts EXCEPT S3.
|
||||
IRAM_ATTR inline uint32_t _PM_timerGetCount(Protomatter_core *core) {
|
||||
return (uint32_t)timerRead((hw_timer_t *)core->timer);
|
||||
}
|
||||
|
||||
#elif defined(CIRCUITPY) // COMPILING FOR CIRCUITPYTHON --------------------
|
||||
|
||||
#endif // END CIRCUITPYTHON ------------------------------------------------
|
||||
|
||||
#endif // END ESP32C3
|
||||
|
|
@ -20,6 +20,8 @@
|
|||
#if defined(ESP32) || \
|
||||
defined(ESP_PLATFORM) // *All* ESP32 variants (OG, S2, S3, etc.)
|
||||
|
||||
#include <inttypes.h>
|
||||
|
||||
#include "esp_idf_version.h"
|
||||
|
||||
// NOTE: there is some intentional repetition in the macros and functions
|
||||
|
|
@ -28,7 +30,6 @@
|
|||
// a change or bugfix in one variant-specific header, check the others to
|
||||
// see if the same should be applied!
|
||||
|
||||
#include "driver/timer.h"
|
||||
#include "soc/gpio_periph.h"
|
||||
|
||||
// As currently written, only one instance of the Protomatter_core struct
|
||||
|
|
@ -39,7 +40,13 @@ Protomatter_core *_PM_protoPtr;
|
|||
|
||||
#if defined(ARDUINO) // COMPILING FOR ARDUINO ------------------------------
|
||||
|
||||
#if ESP_IDF_VERSION < ESP_IDF_VERSION_VAL(5, 0, 0)
|
||||
#define _PM_timerNum 0 // Timer #0 (can be 0-3)
|
||||
static hw_timer_t *_PM_esp32timer = NULL;
|
||||
#define _PM_TIMER_DEFAULT &_PM_esp32timer
|
||||
#else
|
||||
#define _PM_TIMER_DEFAULT ((void *)-1) // some non-NULL but non valid pointer
|
||||
#endif
|
||||
|
||||
// The following defines and functions are common to all ESP32 variants in
|
||||
// the Arduino platform. Anything unique to one variant (or a subset of
|
||||
|
|
@ -48,16 +55,7 @@ Protomatter_core *_PM_protoPtr;
|
|||
// started down that path, it's okay, but move the code out of here and
|
||||
// into the variant-specific headers.
|
||||
|
||||
// This is the default aforementioned singular timer. IN THEORY, other
|
||||
// timers could be used, IF an Arduino sketch passes the address of its
|
||||
// own hw_timer_t* to the Protomatter constructor and initializes that
|
||||
// timer using ESP32's timerBegin(). All of the timer-related functions
|
||||
// below pass around a handle rather than accessing _PM_esp32timer directly,
|
||||
// in case that's ever actually used in the future.
|
||||
static hw_timer_t *_PM_esp32timer = NULL;
|
||||
#define _PM_TIMER_DEFAULT &_PM_esp32timer
|
||||
|
||||
extern IRAM_ATTR void _PM_row_handler(Protomatter_core *core); // In core.c
|
||||
extern void _PM_row_handler(Protomatter_core *core); // In core.c
|
||||
|
||||
// Timer interrupt handler. This, _PM_row_handler() and any functions
|
||||
// called by _PM_row_handler() should all have the IRAM_ATTR attribute
|
||||
|
|
@ -71,9 +69,15 @@ IRAM_ATTR static void _PM_esp32timerCallback(void) {
|
|||
// Set timer period, initialize count value to zero, enable timer.
|
||||
IRAM_ATTR inline void _PM_timerStart(Protomatter_core *core, uint32_t period) {
|
||||
hw_timer_t *timer = (hw_timer_t *)core->timer;
|
||||
#if ESP_IDF_VERSION < ESP_IDF_VERSION_VAL(5, 0, 0)
|
||||
timerAlarmWrite(timer, period, true);
|
||||
timerAlarmEnable(timer);
|
||||
timerStart(timer);
|
||||
#else
|
||||
timerWrite(timer, 0);
|
||||
timerAlarm(timer, period ? period : 1, true, 0);
|
||||
timerStart(timer);
|
||||
#endif
|
||||
}
|
||||
|
||||
// Disable timer and return current count value.
|
||||
|
|
@ -87,11 +91,19 @@ IRAM_ATTR uint32_t _PM_timerStop(Protomatter_core *core) {
|
|||
// that's common to all ESP32 variants; code in variant-specific files might
|
||||
// set up its own special peripherals, then call this.
|
||||
void _PM_esp32commonTimerInit(Protomatter_core *core) {
|
||||
hw_timer_t *timer = (hw_timer_t *)core->timer; // pointer-to-pointer
|
||||
if (timer == _PM_TIMER_DEFAULT) {
|
||||
hw_timer_t *timer_in = (hw_timer_t *)core->timer;
|
||||
if (!timer_in || timer_in == _PM_TIMER_DEFAULT) {
|
||||
#if ESP_IDF_VERSION < ESP_IDF_VERSION_VAL(5, 0, 0)
|
||||
core->timer = timerBegin(_PM_timerNum, 2, true); // 1:2 prescale, count up
|
||||
#else
|
||||
core->timer = timerBegin(_PM_timerFreq);
|
||||
#endif
|
||||
}
|
||||
timerAttachInterrupt(timer, &_PM_esp32timerCallback, true);
|
||||
#if ESP_IDF_VERSION < ESP_IDF_VERSION_VAL(5, 0, 0)
|
||||
timerAttachInterrupt(core->timer, &_PM_esp32timerCallback, true);
|
||||
#else
|
||||
timerAttachInterrupt(core->timer, _PM_esp32timerCallback);
|
||||
#endif
|
||||
}
|
||||
|
||||
#elif defined(CIRCUITPY) // COMPILING FOR CIRCUITPYTHON --------------------
|
||||
|
|
@ -106,7 +118,12 @@ void _PM_esp32commonTimerInit(Protomatter_core *core) {
|
|||
#include "driver/gpio.h"
|
||||
#include "esp_idf_version.h"
|
||||
#include "hal/timer_ll.h"
|
||||
#include "peripherals/timer.h"
|
||||
#if ESP_IDF_VERSION_MAJOR == 5
|
||||
#include "driver/gptimer.h"
|
||||
#include "esp_memory_utils.h"
|
||||
#else
|
||||
#include "driver/timer.h"
|
||||
#endif
|
||||
|
||||
#define _PM_TIMER_DEFAULT NULL
|
||||
#define _PM_pinOutput(pin) gpio_set_direction((pin), GPIO_MODE_OUTPUT)
|
||||
|
|
@ -118,8 +135,24 @@ void _PM_esp32commonTimerInit(Protomatter_core *core) {
|
|||
// (RAM-resident functions). This isn't really the ISR itself, but a
|
||||
// callback invoked by the real ISR (in arduino-esp32's esp32-hal-timer.c)
|
||||
// which takes care of interrupt status bits & such.
|
||||
#if ESP_IDF_VERSION_MAJOR == 5
|
||||
// This is "private" for now. We link to it anyway because there isn't a more
|
||||
// public method yet.
|
||||
extern bool spi_flash_cache_enabled(void);
|
||||
static IRAM_ATTR bool
|
||||
_PM_esp32timerCallback(gptimer_handle_t timer,
|
||||
const gptimer_alarm_event_data_t *event, void *unused) {
|
||||
#else
|
||||
static IRAM_ATTR bool _PM_esp32timerCallback(void *unused) {
|
||||
#endif
|
||||
#if ESP_IDF_VERSION_MAJOR == 5
|
||||
// Some functions and data used by _PM_row_handler may exist in external flash
|
||||
// or PSRAM so we can't run them when their access is disabled (through the
|
||||
// flash cache.)
|
||||
if (_PM_protoPtr && spi_flash_cache_enabled()) {
|
||||
#else
|
||||
if (_PM_protoPtr) {
|
||||
#endif
|
||||
_PM_row_handler(_PM_protoPtr); // In core.c
|
||||
}
|
||||
return false;
|
||||
|
|
@ -127,14 +160,16 @@ static IRAM_ATTR bool _PM_esp32timerCallback(void *unused) {
|
|||
|
||||
// Set timer period, initialize count value to zero, enable timer.
|
||||
#if (ESP_IDF_VERSION_MAJOR == 5)
|
||||
static IRAM_ATTR void _PM_timerStart(Protomatter_core *core, uint32_t period) {
|
||||
timer_index_t *timer = (timer_index_t *)core->timer;
|
||||
timer_ll_enable_counter(timer->hw, timer->idx, false);
|
||||
timer_ll_set_reload_value(timer->hw, timer->idx, 0);
|
||||
timer_ll_trigger_soft_reload(timer->hw, timer->idx);
|
||||
timer_ll_set_alarm_value(timer->hw, timer->idx, period);
|
||||
timer_ll_enable_alarm(timer->hw, timer->idx, true);
|
||||
timer_ll_enable_counter(timer->hw, timer->idx, true);
|
||||
IRAM_ATTR void _PM_timerStart(Protomatter_core *core, uint32_t period) {
|
||||
gptimer_handle_t timer = (gptimer_handle_t)core->timer;
|
||||
|
||||
gptimer_alarm_config_t alarm_config = {
|
||||
.reload_count = 0, // counter will reload with 0 on alarm event
|
||||
.alarm_count = period, // period in ms
|
||||
.flags.auto_reload_on_alarm = true, // enable auto-reload
|
||||
};
|
||||
gptimer_set_alarm_action(timer, &alarm_config);
|
||||
gptimer_start(timer);
|
||||
}
|
||||
#else
|
||||
IRAM_ATTR void _PM_timerStart(Protomatter_core *core, uint32_t period) {
|
||||
|
|
@ -150,10 +185,11 @@ IRAM_ATTR void _PM_timerStart(Protomatter_core *core, uint32_t period) {
|
|||
// Disable timer and return current count value.
|
||||
// Timer must be previously initialized.
|
||||
IRAM_ATTR uint32_t _PM_timerStop(Protomatter_core *core) {
|
||||
timer_index_t *timer = (timer_index_t *)core->timer;
|
||||
#if (ESP_IDF_VERSION_MAJOR == 5)
|
||||
timer_ll_enable_counter(timer->hw, timer->idx, false);
|
||||
gptimer_handle_t timer = (gptimer_handle_t)core->timer;
|
||||
gptimer_stop(timer);
|
||||
#else
|
||||
timer_index_t *timer = (timer_index_t *)core->timer;
|
||||
timer_ll_set_counter_enable(timer->hw, timer->idx, false);
|
||||
#endif
|
||||
return _PM_timerGetCount(core);
|
||||
|
|
@ -161,10 +197,17 @@ IRAM_ATTR uint32_t _PM_timerStop(Protomatter_core *core) {
|
|||
|
||||
#if !defined(CONFIG_IDF_TARGET_ESP32S3)
|
||||
IRAM_ATTR uint32_t _PM_timerGetCount(Protomatter_core *core) {
|
||||
#if (ESP_IDF_VERSION_MAJOR == 5)
|
||||
gptimer_handle_t timer = (gptimer_handle_t)core->timer;
|
||||
uint64_t raw_count;
|
||||
gptimer_get_raw_count(timer, &raw_count);
|
||||
return (uint32_t)raw_count;
|
||||
#else
|
||||
timer_index_t *timer = (timer_index_t *)core->timer;
|
||||
uint64_t result;
|
||||
timer_ll_get_counter_value(timer->hw, timer->idx, &result);
|
||||
return (uint32_t)result;
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
@ -172,6 +215,16 @@ IRAM_ATTR uint32_t _PM_timerGetCount(Protomatter_core *core) {
|
|||
// that's common to all ESP32 variants; code in variant-specific files might
|
||||
// set up its own special peripherals, then call this.
|
||||
static void _PM_esp32commonTimerInit(Protomatter_core *core) {
|
||||
|
||||
#if (ESP_IDF_VERSION_MAJOR == 5)
|
||||
gptimer_handle_t timer = (gptimer_handle_t)core->timer;
|
||||
gptimer_event_callbacks_t cbs = {
|
||||
.on_alarm = _PM_esp32timerCallback, // register user callback
|
||||
};
|
||||
gptimer_register_event_callbacks(timer, &cbs, NULL);
|
||||
|
||||
gptimer_enable(timer);
|
||||
#else
|
||||
timer_index_t *timer = (timer_index_t *)core->timer;
|
||||
const timer_config_t config = {
|
||||
.alarm_en = false,
|
||||
|
|
@ -186,6 +239,7 @@ static void _PM_esp32commonTimerInit(Protomatter_core *core) {
|
|||
timer_isr_callback_add(timer->group, timer->idx, _PM_esp32timerCallback, NULL,
|
||||
0);
|
||||
timer_enable_intr(timer->group, timer->idx);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // END CIRCUITPYTHON ------------------------------------------------
|
||||
|
|
|
|||
|
|
@ -90,6 +90,7 @@ IRAM_ATTR inline uint32_t _PM_timerGetCount(Protomatter_core *core) {
|
|||
#else
|
||||
#include <driver/periph_ctrl.h>
|
||||
#endif
|
||||
#include <driver/gpio.h>
|
||||
#include <esp_private/gdma.h>
|
||||
#include <esp_rom_gpio.h>
|
||||
#include <hal/dma_types.h>
|
||||
|
|
@ -128,12 +129,10 @@ IRAM_ATTR static void blast_long(Protomatter_core *core, uint32_t *data) {}
|
|||
|
||||
static void pinmux(int8_t pin, uint8_t signal) {
|
||||
esp_rom_gpio_connect_out_signal(pin, signal, false, false);
|
||||
gpio_hal_iomux_func_sel(GPIO_PIN_MUX_REG[pin], PIN_FUNC_GPIO);
|
||||
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[pin], PIN_FUNC_GPIO);
|
||||
gpio_set_drive_capability((gpio_num_t)pin, GPIO_DRIVE_STRENGTH);
|
||||
}
|
||||
|
||||
#if defined(ARDUINO) // COMPILING FOR ARDUINO ------------------------------
|
||||
|
||||
// LCD_CAM requires a complete replacement of the "blast" functions in order
|
||||
// to use the DMA-based peripheral.
|
||||
#define _PM_CUSTOM_BLAST // Disable blast_*() functions in core.c
|
||||
|
|
@ -161,155 +160,23 @@ IRAM_ATTR static void blast_byte(Protomatter_core *core, uint8_t *data) {
|
|||
|
||||
// Timer was cleared to 0 before calling blast_byte(), so this
|
||||
// is the state of the timer immediately after DMA started:
|
||||
#if defined(ARDUINO)
|
||||
dmaSetupTime = (uint32_t)timerRead((hw_timer_t *)core->timer);
|
||||
// See notes near top of this file for what's done with this info.
|
||||
}
|
||||
|
||||
void _PM_timerInit(Protomatter_core *core) {
|
||||
// On S3, initialize the LCD_CAM peripheral and DMA.
|
||||
|
||||
// LCD_CAM isn't enabled by default -- MUST begin with this:
|
||||
periph_module_enable(PERIPH_LCD_CAM_MODULE);
|
||||
periph_module_reset(PERIPH_LCD_CAM_MODULE);
|
||||
|
||||
// Reset LCD bus
|
||||
LCD_CAM.lcd_user.lcd_reset = 1;
|
||||
esp_rom_delay_us(100);
|
||||
|
||||
// Configure LCD clock
|
||||
LCD_CAM.lcd_clock.clk_en = 1; // Enable clock
|
||||
LCD_CAM.lcd_clock.lcd_clk_sel = 3; // PLL160M source
|
||||
LCD_CAM.lcd_clock.lcd_clkm_div_a = 1; // 1/1 fractional divide,
|
||||
LCD_CAM.lcd_clock.lcd_clkm_div_b = 1; // plus prescale below yields...
|
||||
#if LCD_CLK_PRESCALE == 8
|
||||
LCD_CAM.lcd_clock.lcd_clkm_div_num = 7; // 1:8 prescale (20 MHz CLK)
|
||||
#elif LCD_CLK_PRESCALE == 9
|
||||
LCD_CAM.lcd_clock.lcd_clkm_div_num = 8; // 1:9 prescale (17.8 MHz CLK)
|
||||
#else
|
||||
LCD_CAM.lcd_clock.lcd_clkm_div_num = 9; // 1:10 prescale (16 MHz CLK)
|
||||
#endif
|
||||
LCD_CAM.lcd_clock.lcd_ck_out_edge = 0; // PCLK low in first half of cycle
|
||||
LCD_CAM.lcd_clock.lcd_ck_idle_edge = 0; // PCLK low idle
|
||||
LCD_CAM.lcd_clock.lcd_clk_equ_sysclk = 1; // PCLK = CLK (ignore CLKCNT_N)
|
||||
|
||||
// Configure frame format. Some of these could probably be skipped and
|
||||
// use defaults, but being verbose for posterity...
|
||||
LCD_CAM.lcd_ctrl.lcd_rgb_mode_en = 0; // i8080 mode (not RGB)
|
||||
LCD_CAM.lcd_rgb_yuv.lcd_conv_bypass = 0; // Disable RGB/YUV converter
|
||||
LCD_CAM.lcd_misc.lcd_next_frame_en = 0; // Do NOT auto-frame
|
||||
LCD_CAM.lcd_data_dout_mode.val = 0; // No data delays
|
||||
LCD_CAM.lcd_user.lcd_always_out_en = 0; // Only when requested
|
||||
LCD_CAM.lcd_user.lcd_8bits_order = 0; // Do not swap bytes
|
||||
LCD_CAM.lcd_user.lcd_bit_order = 0; // Do not reverse bit order
|
||||
LCD_CAM.lcd_user.lcd_2byte_en = 0; // 8-bit data mode
|
||||
// MUST enable at least one dummy phase at start of output, else clock and
|
||||
// data are randomly misaligned by 1-2 cycles following required TX FIFO
|
||||
// reset in blast_byte(). One phase MOSTLY works but sparkles a tiny bit
|
||||
// (as in still very occasionally misaligned by 1 cycle). Two seems ideal;
|
||||
// no sparkle. Since HUB75 is just a shift register, the extra clock ticks
|
||||
// are harmless and the zero-data shifts off end of the chain.
|
||||
LCD_CAM.lcd_user.lcd_dummy = 1; // Enable dummy phase(s) @ LCD start
|
||||
LCD_CAM.lcd_user.lcd_dummy_cyclelen = 1; // 2 dummy phases
|
||||
LCD_CAM.lcd_user.lcd_cmd = 0; // No command at LCD start
|
||||
LCD_CAM.lcd_user.lcd_cmd_2_cycle_en = 0;
|
||||
LCD_CAM.lcd_user.lcd_update = 1;
|
||||
|
||||
// Configure signal pins. IN THEORY this could be expanded to support
|
||||
// 2 parallel chains, but the rest of the LCD & DMA setup is not currently
|
||||
// written for that, so it's limited to a single chain for now.
|
||||
const uint8_t signal[] = {LCD_DATA_OUT0_IDX, LCD_DATA_OUT1_IDX,
|
||||
LCD_DATA_OUT2_IDX, LCD_DATA_OUT3_IDX,
|
||||
LCD_DATA_OUT4_IDX, LCD_DATA_OUT5_IDX};
|
||||
for (int i = 0; i < 6; i++)
|
||||
pinmux(core->rgbPins[i], signal[i]);
|
||||
pinmux(core->clockPin, LCD_PCLK_IDX);
|
||||
gpio_set_drive_capability(core->latch.pin, GPIO_DRIVE_STRENGTH);
|
||||
gpio_set_drive_capability(core->oe.pin, GPIO_DRIVE_STRENGTH);
|
||||
for (uint8_t i = 0; i < core->numAddressLines; i++) {
|
||||
gpio_set_drive_capability(core->addr[i].pin, GPIO_DRIVE_STRENGTH);
|
||||
}
|
||||
|
||||
// Disable LCD_CAM interrupts, clear any pending interrupt
|
||||
LCD_CAM.lc_dma_int_ena.val &= ~LCD_LL_EVENT_TRANS_DONE;
|
||||
LCD_CAM.lc_dma_int_clr.val = 0x03;
|
||||
|
||||
// Set up DMA TX descriptor
|
||||
desc.dw0.owner = DMA_DESCRIPTOR_BUFFER_OWNER_DMA;
|
||||
desc.dw0.suc_eof = 1;
|
||||
desc.dw0.size = desc.dw0.length = core->chainBits;
|
||||
desc.buffer = core->screenData;
|
||||
desc.next = NULL;
|
||||
|
||||
// Alloc DMA channel & connect it to LCD periph
|
||||
gdma_channel_alloc_config_t dma_chan_config = {
|
||||
.sibling_chan = NULL,
|
||||
.direction = GDMA_CHANNEL_DIRECTION_TX,
|
||||
.flags = {.reserve_sibling = 0}};
|
||||
esp_err_t ret = gdma_new_channel(&dma_chan_config, &dma_chan);
|
||||
(void)ret;
|
||||
gdma_connect(dma_chan, GDMA_MAKE_TRIGGER(GDMA_TRIG_PERIPH_LCD, 0));
|
||||
gdma_strategy_config_t strategy_config = {.owner_check = false,
|
||||
.auto_update_desc = false};
|
||||
gdma_apply_strategy(dma_chan, &strategy_config);
|
||||
gdma_transfer_ability_t ability = {
|
||||
.sram_trans_align = 0,
|
||||
.psram_trans_align = 0,
|
||||
};
|
||||
gdma_set_transfer_ability(dma_chan, &ability);
|
||||
gdma_start(dma_chan, (intptr_t)&desc);
|
||||
|
||||
// Enable TRANS_DONE interrupt. Note that we do NOT require nor install
|
||||
// an interrupt service routine, but DO need to enable the TRANS_DONE
|
||||
// flag to make the LCD DMA transfer work.
|
||||
LCD_CAM.lc_dma_int_ena.val |= LCD_LL_EVENT_TRANS_DONE & 0x03;
|
||||
|
||||
_PM_esp32commonTimerInit(core); // In esp32-common.h
|
||||
}
|
||||
|
||||
#elif defined(CIRCUITPY) // COMPILING FOR CIRCUITPYTHON --------------------
|
||||
|
||||
// LCD_CAM requires a complete replacement of the "blast" functions in order
|
||||
// to use the DMA-based peripheral.
|
||||
#define _PM_CUSTOM_BLAST // Disable blast_*() functions in core.c
|
||||
IRAM_ATTR static void blast_byte(Protomatter_core *core, uint8_t *data) {
|
||||
// Reset LCD DOUT parameters each time (required).
|
||||
// IN PRINCIPLE, cyclelen should be chainBits-1 (resulting in chainBits
|
||||
// cycles). But due to the required dummy phases at start of transfer,
|
||||
// extend by 1; set to chainBits, issue chainBits+1 cycles.
|
||||
LCD_CAM.lcd_user.lcd_dout_cyclelen = core->chainBits;
|
||||
LCD_CAM.lcd_user.lcd_dout = 1;
|
||||
LCD_CAM.lcd_user.lcd_update = 1;
|
||||
|
||||
// Reset LCD TX FIFO each time, else we see old data. When doing this,
|
||||
// it's REQUIRED in the setup code to enable at least one dummy pulse,
|
||||
// else the PCLK & data are randomly misaligned by 1-2 clocks!
|
||||
LCD_CAM.lcd_misc.lcd_afifo_reset = 1;
|
||||
|
||||
// Partially re-init descriptor each time (required)
|
||||
desc.dw0.size = desc.dw0.length = core->chainBits;
|
||||
desc.buffer = data;
|
||||
gdma_start(dma_chan, (intptr_t)&desc);
|
||||
esp_rom_delay_us(1); // Necessary before starting xfer
|
||||
|
||||
LCD_CAM.lcd_user.lcd_start = 1; // Begin LCD DMA xfer
|
||||
|
||||
// Timer was cleared to 0 before calling blast_byte(), so this
|
||||
// is the state of the timer immediately after DMA started:
|
||||
#elif defined(CIRCUITPY)
|
||||
uint64_t value;
|
||||
#if (ESP_IDF_VERSION_MAJOR == 5)
|
||||
gptimer_handle_t timer = (gptimer_handle_t)core->timer;
|
||||
gptimer_get_raw_count(timer, &value);
|
||||
#else
|
||||
timer_index_t *timer = (timer_index_t *)core->timer;
|
||||
timer_get_counter_value(timer->group, timer->idx, &value);
|
||||
#endif
|
||||
dmaSetupTime = (uint32_t)value;
|
||||
#endif
|
||||
// See notes near top of this file for what's done with this info.
|
||||
}
|
||||
|
||||
static void _PM_timerInit(Protomatter_core *core) {
|
||||
|
||||
// TO DO: adapt this function for any CircuitPython-specific changes.
|
||||
// If none are required, this function can be deleted and the version
|
||||
// above can be moved before the ARDUIO/CIRCUITPY checks. If minimal
|
||||
// changes, consider a single _PM_timerInit() implementation with
|
||||
// ARDUINO/CIRCUITPY checks inside. It's all good.
|
||||
|
||||
// On S3, initialize the LCD_CAM peripheral and DMA.
|
||||
|
||||
// LCD_CAM isn't enabled by default -- MUST begin with this:
|
||||
|
|
@ -385,7 +252,9 @@ static void _PM_timerInit(Protomatter_core *core) {
|
|||
desc.next = NULL;
|
||||
|
||||
// Alloc DMA channel & connect it to LCD periph
|
||||
#if defined(CIRCUITPY)
|
||||
if (dma_chan == NULL) {
|
||||
#endif
|
||||
gdma_channel_alloc_config_t dma_chan_config = {
|
||||
.sibling_chan = NULL,
|
||||
.direction = GDMA_CHANNEL_DIRECTION_TX,
|
||||
|
|
@ -400,7 +269,9 @@ static void _PM_timerInit(Protomatter_core *core) {
|
|||
.psram_trans_align = 0,
|
||||
};
|
||||
gdma_set_transfer_ability(dma_chan, &ability);
|
||||
#if defined(CIRCUITPY)
|
||||
}
|
||||
#endif
|
||||
gdma_start(dma_chan, (intptr_t)&desc);
|
||||
|
||||
// Enable TRANS_DONE interrupt. Note that we do NOT require nor install
|
||||
|
|
@ -411,6 +282,4 @@ static void _PM_timerInit(Protomatter_core *core) {
|
|||
_PM_esp32commonTimerInit(core); // In esp32-common.h
|
||||
}
|
||||
|
||||
#endif // END CIRCUITPYTHON ------------------------------------------------
|
||||
|
||||
#endif // END ESP32S3
|
||||
|
|
|
|||
|
|
@ -32,7 +32,7 @@
|
|||
#define _PM_portClearRegister(pin) \
|
||||
(volatile uint32_t *)((pin < 32) ? &GPIO.out_w1tc : &GPIO.out1_w1tc.val)
|
||||
|
||||
#define _PM_portBitMask(pin) (1U << ((pin)&31))
|
||||
#define _PM_portBitMask(pin) (1U << ((pin) & 31))
|
||||
|
||||
#if __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
|
||||
#define _PM_byteOffset(pin) ((pin & 31) / 8)
|
||||
|
|
|
|||
|
|
@ -99,7 +99,7 @@ volatile uint32_t *_PM_portClearRegister(uint32_t pin) {
|
|||
#define _PM_pinInput(pin) nrf_gpio_cfg_input(pin)
|
||||
#define _PM_pinHigh(pin) nrf_gpio_pin_set(pin)
|
||||
#define _PM_pinLow(pin) nrf_gpio_pin_clear(pin)
|
||||
#define _PM_portBitMask(pin) (1u << ((pin)&31))
|
||||
#define _PM_portBitMask(pin) (1u << ((pin) & 31))
|
||||
|
||||
#if __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
|
||||
#define _PM_byteOffset(pin) ((pin & 31) / 8)
|
||||
|
|
|
|||
|
|
@ -26,7 +26,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#if defined(ARDUINO_ARCH_RP2040) || defined(PICO_BOARD) || defined(__RP2040__)
|
||||
#if defined(ARDUINO_ARCH_RP2040) || defined(PICO_BOARD) || \
|
||||
defined(__RP2040__) || defined(__RP2350__)
|
||||
|
||||
#include "../../hardware_pwm/include/hardware/pwm.h"
|
||||
#include "hardware/irq.h"
|
||||
|
|
@ -105,8 +106,13 @@ void _PM_timerInit(Protomatter_core *core) {
|
|||
#elif defined(CIRCUITPY) // COMPILING FOR CIRCUITPYTHON --------------------
|
||||
|
||||
#if !defined(F_CPU) // Not sure if CircuitPython build defines this
|
||||
#ifdef __RP2040__
|
||||
#define F_CPU 125000000 // Standard RP2040 clock speed
|
||||
#endif
|
||||
#ifdef __RP2350__
|
||||
#define F_CPU 150000000 // Standard RP2350 clock speed
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// 'pin' here is GPXX #
|
||||
#if __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
|
||||
|
|
@ -240,10 +246,10 @@ uint32_t _PM_timerStop(Protomatter_core *core) {
|
|||
#define _PM_clockHoldLow asm("nop; nop; nop;");
|
||||
#define _PM_clockHoldHigh asm("nop; nop; nop;");
|
||||
#elif (F_CPU >= 175000000)
|
||||
#define _PM_clockHoldLow asm("nop; nop;");
|
||||
#define _PM_clockHoldLow asm("nop; nop; nop;");
|
||||
#define _PM_clockHoldHigh asm("nop;");
|
||||
#elif (F_CPU >= 125000000)
|
||||
#define _PM_clockHoldLow asm("nop;");
|
||||
#define _PM_clockHoldLow asm("nop; nop; nop;");
|
||||
#define _PM_clockHoldHigh asm("nop;");
|
||||
#elif (F_CPU >= 100000000)
|
||||
#define _PM_clockHoldLow asm("nop;");
|
||||
|
|
|
|||
|
|
@ -64,7 +64,7 @@ void _PM_IRQ_HANDLER(void) {
|
|||
#define _PM_pinInput(pin) gpio_set_pin_direction(pin, GPIO_DIRECTION_IN)
|
||||
#define _PM_pinHigh(pin) gpio_set_pin_level(pin, 1)
|
||||
#define _PM_pinLow(pin) gpio_set_pin_level(pin, 0)
|
||||
#define _PM_portBitMask(pin) (1u << ((pin)&31))
|
||||
#define _PM_portBitMask(pin) (1u << ((pin) & 31))
|
||||
|
||||
#if __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
|
||||
#define _PM_byteOffset(pin) ((pin & 31) / 8)
|
||||
|
|
|
|||
|
|
@ -47,6 +47,21 @@
|
|||
|
||||
#define F_CPU (120000000)
|
||||
|
||||
// Enable high output driver strength on one pin. Arduino does this by
|
||||
// default on pinMode(OUTPUT), but CircuitPython requires the motions...
|
||||
static void _hi_drive(uint8_t pin) {
|
||||
// For Arduino testing only:
|
||||
// pin = g_APinDescription[pin].ulPort * 32 + g_APinDescription[pin].ulPin;
|
||||
|
||||
// Input, pull-up and peripheral MUX are disabled as we're only using
|
||||
// vanilla PORT writes on Protomatter GPIO.
|
||||
PORT->Group[pin / 32].WRCONFIG.reg =
|
||||
(pin & 16)
|
||||
? PORT_WRCONFIG_WRPINCFG | PORT_WRCONFIG_DRVSTR |
|
||||
PORT_WRCONFIG_HWSEL | (1 << (pin & 15))
|
||||
: PORT_WRCONFIG_WRPINCFG | PORT_WRCONFIG_DRVSTR | (1 << (pin & 15));
|
||||
}
|
||||
|
||||
#else
|
||||
|
||||
// Other port register lookups go here
|
||||
|
|
@ -157,6 +172,20 @@ void _PM_timerInit(Protomatter_core *core) {
|
|||
NVIC_EnableIRQ(timer[timerNum].IRQn);
|
||||
|
||||
// Timer is configured but NOT enabled by default
|
||||
|
||||
#if defined(CIRCUITPY) // See notes earlier; Arduino doesn't need this.
|
||||
// Enable high drive strength on all Protomatter pins. TBH this is kind
|
||||
// of a jerky place to do this (it's not actually related to the timer
|
||||
// peripheral) but Protomatter doesn't really have a spot for it.
|
||||
uint8_t i;
|
||||
for (i = 0; i < core->parallel * 6; i++)
|
||||
_hi_drive(core->rgbPins[i]);
|
||||
for (i = 0; i < core->numAddressLines; i++)
|
||||
_hi_drive(core->addr[i].pin);
|
||||
_hi_drive(core->clockPin);
|
||||
_hi_drive(core->latch.pin);
|
||||
_hi_drive(core->oe.pin);
|
||||
#endif
|
||||
}
|
||||
|
||||
// Set timer period, initialize count value to zero, enable timer.
|
||||
|
|
@ -294,20 +323,27 @@ static void blast_byte(Protomatter_core *core, uint8_t *data) {
|
|||
// clock are all within the same byte of a PORT register, else we'd be
|
||||
// in the word- or long-blasting functions now. So we just need an
|
||||
// 8-bit pointer to the PORT:
|
||||
uint8_t *toggle = (uint8_t *)core->toggleReg + core->portOffset;
|
||||
volatile uint8_t *toggle =
|
||||
(volatile uint8_t *)core->toggleReg + core->portOffset;
|
||||
uint8_t bucket, clock = core->clockMask;
|
||||
// Pointer list must be distinct vars, not an array, else slow.
|
||||
uint8_t *ptr0 = (_PM_duty == _PM_maxDuty) ? toggle : &bucket;
|
||||
uint8_t *ptr1 = (_PM_duty == (_PM_maxDuty - 1)) ? toggle : &bucket;
|
||||
uint8_t *ptr2 = (_PM_duty == (_PM_maxDuty - 2)) ? toggle : &bucket;
|
||||
volatile uint8_t *ptr0 =
|
||||
(_PM_duty == _PM_maxDuty) ? toggle : (volatile uint8_t *)&bucket;
|
||||
volatile uint8_t *ptr1 =
|
||||
(_PM_duty == (_PM_maxDuty - 1)) ? toggle : (volatile uint8_t *)&bucket;
|
||||
volatile uint8_t *ptr2 =
|
||||
(_PM_duty == (_PM_maxDuty - 2)) ? toggle : (volatile uint8_t *)&bucket;
|
||||
#if _PM_maxDuty >= 3
|
||||
uint8_t *ptr3 = (_PM_duty == (_PM_maxDuty - 3)) ? toggle : &bucket;
|
||||
volatile uint8_t *ptr3 =
|
||||
(_PM_duty == (_PM_maxDuty - 3)) ? toggle : (volatile uint8_t *)&bucket;
|
||||
#endif
|
||||
#if _PM_maxDuty >= 4
|
||||
uint8_t *ptr4 = (_PM_duty == (_PM_maxDuty - 4)) ? toggle : &bucket;
|
||||
volatile uint8_t *ptr4 =
|
||||
(_PM_duty == (_PM_maxDuty - 4)) ? toggle : (volatile uint8_t *)&bucket;
|
||||
#endif
|
||||
#if _PM_maxDuty >= 5
|
||||
uint8_t *ptr5 = (_PM_duty == (_PM_maxDuty - 5)) ? toggle : &bucket;
|
||||
volatile uint8_t *ptr5 =
|
||||
(_PM_duty == (_PM_maxDuty - 5)) ? toggle : (volatile uint8_t *)&bucket;
|
||||
#endif
|
||||
uint16_t chunks = core->chainBits / 8;
|
||||
|
||||
|
|
@ -329,19 +365,25 @@ static void blast_byte(Protomatter_core *core, uint8_t *data) {
|
|||
|
||||
// This is a copypasta of blast_byte() with types changed to uint16_t.
|
||||
static void blast_word(Protomatter_core *core, uint16_t *data) {
|
||||
uint16_t *toggle = (uint16_t *)core->toggleReg + core->portOffset;
|
||||
volatile uint16_t *toggle = (uint16_t *)core->toggleReg + core->portOffset;
|
||||
uint16_t bucket, clock = core->clockMask;
|
||||
uint16_t *ptr0 = (_PM_duty == _PM_maxDuty) ? toggle : &bucket;
|
||||
uint16_t *ptr1 = (_PM_duty == (_PM_maxDuty - 1)) ? toggle : &bucket;
|
||||
uint16_t *ptr2 = (_PM_duty == (_PM_maxDuty - 2)) ? toggle : &bucket;
|
||||
volatile uint16_t *ptr0 =
|
||||
(_PM_duty == _PM_maxDuty) ? toggle : (volatile uint16_t *)&bucket;
|
||||
volatile uint16_t *ptr1 =
|
||||
(_PM_duty == (_PM_maxDuty - 1)) ? toggle : (volatile uint16_t *)&bucket;
|
||||
volatile uint16_t *ptr2 =
|
||||
(_PM_duty == (_PM_maxDuty - 2)) ? toggle : (volatile uint16_t *)&bucket;
|
||||
#if _PM_maxDuty >= 3
|
||||
uint16_t *ptr3 = (_PM_duty == (_PM_maxDuty - 3)) ? toggle : &bucket;
|
||||
volatile uint16_t *ptr3 =
|
||||
(_PM_duty == (_PM_maxDuty - 3)) ? toggle : (volatile uint16_t *)&bucket;
|
||||
#endif
|
||||
#if _PM_maxDuty >= 4
|
||||
uint16_t *ptr4 = (_PM_duty == (_PM_maxDuty - 4)) ? toggle : &bucket;
|
||||
volatile uint16_t *ptr4 =
|
||||
(_PM_duty == (_PM_maxDuty - 4)) ? toggle : (volatile uint16_t *)&bucket;
|
||||
#endif
|
||||
#if _PM_maxDuty >= 5
|
||||
uint16_t *ptr5 = (_PM_duty == (_PM_maxDuty - 5)) ? toggle : &bucket;
|
||||
volatile uint16_t *ptr5 =
|
||||
(_PM_duty == (_PM_maxDuty - 5)) ? toggle : (volatile uint16_t *)&bucket;
|
||||
#endif
|
||||
uint16_t chunks = core->chainBits / 8;
|
||||
do {
|
||||
|
|
@ -353,19 +395,25 @@ static void blast_word(Protomatter_core *core, uint16_t *data) {
|
|||
|
||||
// This is a copypasta of blast_byte() with types changed to uint32_t.
|
||||
static void blast_long(Protomatter_core *core, uint32_t *data) {
|
||||
uint32_t *toggle = (uint32_t *)core->toggleReg;
|
||||
volatile uint32_t *toggle = (uint32_t *)core->toggleReg;
|
||||
uint32_t bucket, clock = core->clockMask;
|
||||
uint32_t *ptr0 = (_PM_duty == _PM_maxDuty) ? toggle : &bucket;
|
||||
uint32_t *ptr1 = (_PM_duty == (_PM_maxDuty - 1)) ? toggle : &bucket;
|
||||
uint32_t *ptr2 = (_PM_duty == (_PM_maxDuty - 2)) ? toggle : &bucket;
|
||||
volatile uint32_t *ptr0 =
|
||||
(_PM_duty == _PM_maxDuty) ? toggle : (volatile uint32_t *)&bucket;
|
||||
volatile uint32_t *ptr1 =
|
||||
(_PM_duty == (_PM_maxDuty - 1)) ? toggle : (volatile uint32_t *)&bucket;
|
||||
volatile uint32_t *ptr2 =
|
||||
(_PM_duty == (_PM_maxDuty - 2)) ? toggle : (volatile uint32_t *)&bucket;
|
||||
#if _PM_maxDuty >= 3
|
||||
uint32_t *ptr3 = (_PM_duty == (_PM_maxDuty - 3)) ? toggle : &bucket;
|
||||
volatile uint32_t *ptr3 =
|
||||
(_PM_duty == (_PM_maxDuty - 3)) ? toggle : (volatile uint32_t *)&bucket;
|
||||
#endif
|
||||
#if _PM_maxDuty >= 4
|
||||
uint32_t *ptr4 = (_PM_duty == (_PM_maxDuty - 4)) ? toggle : &bucket;
|
||||
volatile uint32_t *ptr4 =
|
||||
(_PM_duty == (_PM_maxDuty - 4)) ? toggle : (volatile uint32_t *)&bucket;
|
||||
#endif
|
||||
#if _PM_maxDuty >= 5
|
||||
uint32_t *ptr5 = (_PM_duty == (_PM_maxDuty - 5)) ? toggle : &bucket;
|
||||
volatile uint32_t *ptr5 =
|
||||
(_PM_duty == (_PM_maxDuty - 5)) ? toggle : (volatile uint32_t *)&bucket;
|
||||
#endif
|
||||
uint16_t chunks = core->chainBits / 8;
|
||||
do {
|
||||
|
|
|
|||
|
|
@ -28,7 +28,7 @@
|
|||
#include "timers.h"
|
||||
|
||||
#undef _PM_portBitMask
|
||||
#define _PM_portBitMask(pin) (1u << ((pin)&15))
|
||||
#define _PM_portBitMask(pin) (1u << ((pin) & 15))
|
||||
#define _PM_byteOffset(pin) ((pin & 15) / 8)
|
||||
#define _PM_wordOffset(pin) ((pin & 15) / 16)
|
||||
|
||||
|
|
@ -83,7 +83,7 @@ volatile uint16_t *_PM_portClearRegister(uint32_t pin) {
|
|||
// TODO: this is no longer true, should it change?
|
||||
void *_PM_protoPtr = NULL;
|
||||
|
||||
STATIC TIM_HandleTypeDef tim_handle;
|
||||
static TIM_HandleTypeDef tim_handle;
|
||||
|
||||
// Timer interrupt service routine
|
||||
void _PM_IRQ_HANDLER(void) {
|
||||
|
|
|
|||
39
src/core.c
39
src/core.c
|
|
@ -95,8 +95,9 @@ ProtomatterStatus _PM_init(Protomatter_core *core, uint16_t bitWidth,
|
|||
uint8_t addrCount, uint8_t *addrList,
|
||||
uint8_t clockPin, uint8_t latchPin, uint8_t oePin,
|
||||
bool doubleBuffer, int8_t tile, void *timer) {
|
||||
if (!core)
|
||||
if (!core) {
|
||||
return PROTOMATTER_ERR_ARG;
|
||||
}
|
||||
|
||||
// bitDepth is NOT constrained here, handle in calling function
|
||||
// (varies with implementation, e.g. GFX lib is max 6 bitplanes,
|
||||
|
|
@ -1199,18 +1200,24 @@ void _PM_convert_565_word(Protomatter_core *core, uint16_t *source,
|
|||
uint16_t upperRGB = upperSrc[srcIdx]; // Pixel in upper half
|
||||
uint16_t lowerRGB = lowerSrc[srcIdx]; // Pixel in lower half
|
||||
uint16_t result = 0;
|
||||
if (upperRGB & redBit)
|
||||
if (upperRGB & redBit) {
|
||||
result |= pinMask[0];
|
||||
if (upperRGB & greenBit)
|
||||
}
|
||||
if (upperRGB & greenBit) {
|
||||
result |= pinMask[1];
|
||||
if (upperRGB & blueBit)
|
||||
}
|
||||
if (upperRGB & blueBit) {
|
||||
result |= pinMask[2];
|
||||
if (lowerRGB & redBit)
|
||||
}
|
||||
if (lowerRGB & redBit) {
|
||||
result |= pinMask[3];
|
||||
if (lowerRGB & greenBit)
|
||||
}
|
||||
if (lowerRGB & greenBit) {
|
||||
result |= pinMask[4];
|
||||
if (lowerRGB & blueBit)
|
||||
}
|
||||
if (lowerRGB & blueBit) {
|
||||
result |= pinMask[5];
|
||||
}
|
||||
// Main difference here vs byte converter is each chain
|
||||
// ORs new bits into place (vs single-pass overwrite).
|
||||
// #if defined(_PM_portToggleRegister)
|
||||
|
|
@ -1323,18 +1330,24 @@ void _PM_convert_565_long(Protomatter_core *core, uint16_t *source,
|
|||
uint16_t upperRGB = upperSrc[srcIdx]; // Pixel in upper half
|
||||
uint16_t lowerRGB = lowerSrc[srcIdx]; // Pixel in lower half
|
||||
uint32_t result = 0;
|
||||
if (upperRGB & redBit)
|
||||
if (upperRGB & redBit) {
|
||||
result |= pinMask[0];
|
||||
if (upperRGB & greenBit)
|
||||
}
|
||||
if (upperRGB & greenBit) {
|
||||
result |= pinMask[1];
|
||||
if (upperRGB & blueBit)
|
||||
}
|
||||
if (upperRGB & blueBit) {
|
||||
result |= pinMask[2];
|
||||
if (lowerRGB & redBit)
|
||||
}
|
||||
if (lowerRGB & redBit) {
|
||||
result |= pinMask[3];
|
||||
if (lowerRGB & greenBit)
|
||||
}
|
||||
if (lowerRGB & greenBit) {
|
||||
result |= pinMask[4];
|
||||
if (lowerRGB & blueBit)
|
||||
}
|
||||
if (lowerRGB & blueBit) {
|
||||
result |= pinMask[5];
|
||||
}
|
||||
// Main difference here vs byte converter is each chain
|
||||
// ORs new bits into place (vs single-pass overwrite).
|
||||
// #if defined(_PM_portToggleRegister)
|
||||
|
|
|
|||
Loading…
Reference in a new issue