summaryrefslogtreecommitdiff
path: root/drivers
diff options
context:
space:
mode:
Diffstat (limited to 'drivers')
-rw-r--r--drivers/bluetooth/bluefruit_le.cpp (renamed from drivers/bluetooth/adafruit_ble.cpp)84
-rw-r--r--drivers/bluetooth/bluefruit_le.h (renamed from drivers/bluetooth/adafruit_ble.h)20
-rw-r--r--drivers/bluetooth/outputselect.c23
-rw-r--r--drivers/bluetooth/rn42.c101
-rw-r--r--drivers/bluetooth/rn42.h25
-rw-r--r--drivers/eeprom/eeprom_driver.c12
-rw-r--r--drivers/eeprom/eeprom_i2c.c6
-rw-r--r--drivers/eeprom/eeprom_spi.c12
-rw-r--r--drivers/eeprom/eeprom_transient.c8
-rw-r--r--drivers/eeprom/eeprom_transient.h2
-rw-r--r--drivers/flash/flash_spi.c376
-rw-r--r--drivers/flash/flash_spi.h136
-rw-r--r--drivers/gpio/mcp23018.c108
-rw-r--r--drivers/gpio/mcp23018.h65
-rw-r--r--drivers/gpio/pca9555.c61
-rw-r--r--drivers/gpio/pca9555.h81
-rw-r--r--drivers/gpio/sn74x138.c65
-rw-r--r--drivers/gpio/sn74x138.h48
-rw-r--r--drivers/haptic/DRV2605L.c6
-rw-r--r--drivers/haptic/solenoid.c20
-rw-r--r--drivers/lcd/st7565.c25
-rw-r--r--drivers/lcd/st7565.h8
-rw-r--r--drivers/led/apa102.c10
-rw-r--r--drivers/led/aw20216.c14
-rw-r--r--drivers/led/ckled2001.c11
-rw-r--r--drivers/led/issi/is31fl3731-simple.c6
-rw-r--r--drivers/led/issi/is31fl3731.c6
-rw-r--r--drivers/led/issi/is31fl3733-simple.c248
-rw-r--r--drivers/led/issi/is31fl3733-simple.h260
-rw-r--r--drivers/led/issi/is31fl3733.c20
-rw-r--r--drivers/led/issi/is31fl3733.h14
-rw-r--r--drivers/led/issi/is31fl3736.c20
-rw-r--r--drivers/led/issi/is31fl3736.h16
-rw-r--r--drivers/led/issi/is31fl3737.c20
-rw-r--r--drivers/led/issi/is31fl3737.h16
-rw-r--r--drivers/led/issi/is31fl3741.c20
-rw-r--r--drivers/led/issi/is31fl3741.h16
-rw-r--r--drivers/led/issi/is31fl3742.h299
-rw-r--r--drivers/led/issi/is31fl3743.h327
-rw-r--r--drivers/led/issi/is31fl3745.h270
-rw-r--r--drivers/led/issi/is31fl3746.h198
-rw-r--r--drivers/led/issi/is31flcommon.c230
-rw-r--r--drivers/led/issi/is31flcommon.h78
-rw-r--r--drivers/oled/oled_driver.h22
-rw-r--r--drivers/oled/ssd1306_sh1106.c49
-rw-r--r--drivers/ps2/ps2_busywait.c6
-rw-r--r--drivers/ps2/ps2_interrupt.c16
-rw-r--r--drivers/ps2/ps2_mouse.c28
-rw-r--r--drivers/sensors/adns5050.c10
-rw-r--r--drivers/sensors/adns9800.c20
-rw-r--r--drivers/sensors/adns9800_srom_A6.h2
-rw-r--r--drivers/sensors/analog_joystick.c2
-rw-r--r--drivers/sensors/cirque_pinnacle.c38
-rw-r--r--drivers/sensors/cirque_pinnacle.h8
-rw-r--r--drivers/sensors/cirque_pinnacle_i2c.c4
-rw-r--r--drivers/sensors/cirque_pinnacle_spi.c10
-rw-r--r--drivers/sensors/pimoroni_trackball.c24
-rw-r--r--drivers/sensors/pimoroni_trackball.h9
-rw-r--r--drivers/sensors/pmw3360.c287
-rw-r--r--drivers/sensors/pmw3360.h43
-rw-r--r--drivers/sensors/pmw3389.c294
-rw-r--r--drivers/sensors/pmw3389.h76
-rw-r--r--drivers/sensors/pmw3389_firmware.h558
-rw-r--r--drivers/serial.h19
-rw-r--r--drivers/usb2422.c14
-rw-r--r--drivers/ws2812.h8
66 files changed, 4127 insertions, 811 deletions
diff --git a/drivers/bluetooth/adafruit_ble.cpp b/drivers/bluetooth/bluefruit_le.cpp
index 34a780e9a5..19310767cf 100644
--- a/drivers/bluetooth/adafruit_ble.cpp
+++ b/drivers/bluetooth/bluefruit_le.cpp
@@ -1,4 +1,4 @@
-#include "adafruit_ble.h"
+#include "bluefruit_le.h"
#include <stdio.h>
#include <stdlib.h>
@@ -16,20 +16,20 @@
// These are the pin assignments for the 32u4 boards.
// You may define them to something else in your config.h
// if yours is wired up differently.
-#ifndef ADAFRUIT_BLE_RST_PIN
-# define ADAFRUIT_BLE_RST_PIN D4
+#ifndef BLUEFRUIT_LE_RST_PIN
+# define BLUEFRUIT_LE_RST_PIN D4
#endif
-#ifndef ADAFRUIT_BLE_CS_PIN
-# define ADAFRUIT_BLE_CS_PIN B4
+#ifndef BLUEFRUIT_LE_CS_PIN
+# define BLUEFRUIT_LE_CS_PIN B4
#endif
-#ifndef ADAFRUIT_BLE_IRQ_PIN
-# define ADAFRUIT_BLE_IRQ_PIN E6
+#ifndef BLUEFRUIT_LE_IRQ_PIN
+# define BLUEFRUIT_LE_IRQ_PIN E6
#endif
-#ifndef ADAFRUIT_BLE_SCK_DIVISOR
-# define ADAFRUIT_BLE_SCK_DIVISOR 2 // 4MHz SCK/8MHz CPU, calculated for Feather 32U4 BLE
+#ifndef BLUEFRUIT_LE_SCK_DIVISOR
+# define BLUEFRUIT_LE_SCK_DIVISOR 2 // 4MHz SCK/8MHz CPU, calculated for Feather 32U4 BLE
#endif
#define SAMPLE_BATTERY
@@ -77,10 +77,10 @@ struct sdep_msg {
// information here.
enum queue_type {
- QTKeyReport, // 1-byte modifier + 6-byte key report
- QTConsumer, // 16-bit key code
+ QTKeyReport, // 1-byte modifier + 6-byte key report
+ QTConsumer, // 16-bit key code
#ifdef MOUSE_ENABLE
- QTMouseMove, // 4-byte mouse report
+ QTMouseMove, // 4-byte mouse report
#endif
};
@@ -115,8 +115,8 @@ enum sdep_type {
SdepResponse = 0x20,
SdepAlert = 0x40,
SdepError = 0x80,
- SdepSlaveNotReady = 0xFE, // Try again later
- SdepSlaveOverflow = 0xFF, // You read more data than is available
+ SdepSlaveNotReady = 0xFE, // Try again later
+ SdepSlaveOverflow = 0xFF, // You read more data than is available
};
enum ble_cmd {
@@ -143,7 +143,7 @@ static bool at_command_P(const char *cmd, char *resp, uint16_t resplen, bool ver
// Send a single SDEP packet
static bool sdep_send_pkt(const struct sdep_msg *msg, uint16_t timeout) {
- spi_start(ADAFRUIT_BLE_CS_PIN, false, 0, ADAFRUIT_BLE_SCK_DIVISOR);
+ spi_start(BLUEFRUIT_LE_CS_PIN, false, 0, BLUEFRUIT_LE_SCK_DIVISOR);
uint16_t timerStart = timer_read();
bool success = false;
bool ready = false;
@@ -157,7 +157,7 @@ static bool sdep_send_pkt(const struct sdep_msg *msg, uint16_t timeout) {
// Release it and let it initialize
spi_stop();
wait_us(SdepBackOff);
- spi_start(ADAFRUIT_BLE_CS_PIN, false, 0, ADAFRUIT_BLE_SCK_DIVISOR);
+ spi_start(BLUEFRUIT_LE_CS_PIN, false, 0, BLUEFRUIT_LE_SCK_DIVISOR);
} while (timer_elapsed(timerStart) < timeout);
if (ready) {
@@ -190,7 +190,7 @@ static bool sdep_recv_pkt(struct sdep_msg *msg, uint16_t timeout) {
bool ready = false;
do {
- ready = readPin(ADAFRUIT_BLE_IRQ_PIN);
+ ready = readPin(BLUEFRUIT_LE_IRQ_PIN);
if (ready) {
break;
}
@@ -198,7 +198,7 @@ static bool sdep_recv_pkt(struct sdep_msg *msg, uint16_t timeout) {
} while (timer_elapsed(timerStart) < timeout);
if (ready) {
- spi_start(ADAFRUIT_BLE_CS_PIN, false, 0, ADAFRUIT_BLE_SCK_DIVISOR);
+ spi_start(BLUEFRUIT_LE_CS_PIN, false, 0, BLUEFRUIT_LE_SCK_DIVISOR);
do {
// Read the command type, waiting for the data to be ready
@@ -207,7 +207,7 @@ static bool sdep_recv_pkt(struct sdep_msg *msg, uint16_t timeout) {
// Release it and let it initialize
spi_stop();
wait_us(SdepBackOff);
- spi_start(ADAFRUIT_BLE_CS_PIN, false, 0, ADAFRUIT_BLE_SCK_DIVISOR);
+ spi_start(BLUEFRUIT_LE_CS_PIN, false, 0, BLUEFRUIT_LE_SCK_DIVISOR);
continue;
}
@@ -233,7 +233,7 @@ static void resp_buf_read_one(bool greedy) {
return;
}
- if (readPin(ADAFRUIT_BLE_IRQ_PIN)) {
+ if (readPin(BLUEFRUIT_LE_IRQ_PIN)) {
struct sdep_msg msg;
again:
@@ -244,7 +244,7 @@ static void resp_buf_read_one(bool greedy) {
dprintf("recv latency %dms\n", TIMER_DIFF_16(timer_read(), last_send));
}
- if (greedy && resp_buf.peek(last_send) && readPin(ADAFRUIT_BLE_IRQ_PIN)) {
+ if (greedy && resp_buf.peek(last_send) && readPin(BLUEFRUIT_LE_IRQ_PIN)) {
goto again;
}
}
@@ -295,24 +295,26 @@ static bool ble_init(void) {
state.configured = false;
state.is_connected = false;
- setPinInput(ADAFRUIT_BLE_IRQ_PIN);
+ setPinInput(BLUEFRUIT_LE_IRQ_PIN);
spi_init();
// Perform a hardware reset
- setPinOutput(ADAFRUIT_BLE_RST_PIN);
- writePinHigh(ADAFRUIT_BLE_RST_PIN);
- writePinLow(ADAFRUIT_BLE_RST_PIN);
+ setPinOutput(BLUEFRUIT_LE_RST_PIN);
+ writePinHigh(BLUEFRUIT_LE_RST_PIN);
+ writePinLow(BLUEFRUIT_LE_RST_PIN);
wait_ms(10);
- writePinHigh(ADAFRUIT_BLE_RST_PIN);
+ writePinHigh(BLUEFRUIT_LE_RST_PIN);
- wait_ms(1000); // Give it a second to initialize
+ wait_ms(1000); // Give it a second to initialize
state.initialized = true;
return state.initialized;
}
-static inline uint8_t min(uint8_t a, uint8_t b) { return a < b ? a : b; }
+static inline uint8_t min(uint8_t a, uint8_t b) {
+ return a < b ? a : b;
+}
static bool read_response(char *resp, uint16_t resplen, bool verbose) {
char *dest = resp;
@@ -424,9 +426,11 @@ bool at_command_P(const char *cmd, char *resp, uint16_t resplen, bool verbose) {
return at_command(cmdbuf, resp, resplen, verbose);
}
-bool adafruit_ble_is_connected(void) { return state.is_connected; }
+bool bluefruit_le_is_connected(void) {
+ return state.is_connected;
+}
-bool adafruit_ble_enable_keyboard(void) {
+bool bluefruit_le_enable_keyboard(void) {
char resbuf[128];
if (!state.initialized && !ble_init()) {
@@ -498,16 +502,16 @@ static void set_connected(bool connected) {
}
}
-void adafruit_ble_task(void) {
+void bluefruit_le_task(void) {
char resbuf[48];
- if (!state.configured && !adafruit_ble_enable_keyboard()) {
+ if (!state.configured && !bluefruit_le_enable_keyboard()) {
return;
}
resp_buf_read_one(true);
send_buf_send_one(SdepShortTimeout);
- if (resp_buf.empty() && (state.event_flags & UsingEvents) && readPin(ADAFRUIT_BLE_IRQ_PIN)) {
+ if (resp_buf.empty() && (state.event_flags & UsingEvents) && readPin(BLUEFRUIT_LE_IRQ_PIN)) {
// Must be an event update
if (at_command_P(PSTR("AT+EVENTSTATUS"), resbuf, sizeof(resbuf))) {
uint32_t mask = strtoul(resbuf, NULL, 16);
@@ -609,7 +613,7 @@ static bool process_queue_item(struct queue_item *item, uint16_t timeout) {
}
}
-void adafruit_ble_send_keys(uint8_t hid_modifier_mask, uint8_t *keys, uint8_t nkeys) {
+void bluefruit_le_send_keys(uint8_t hid_modifier_mask, uint8_t *keys, uint8_t nkeys) {
struct queue_item item;
bool didWait = false;
@@ -643,7 +647,7 @@ void adafruit_ble_send_keys(uint8_t hid_modifier_mask, uint8_t *keys, uint8_t nk
}
}
-void adafruit_ble_send_consumer_key(uint16_t usage) {
+void bluefruit_le_send_consumer_key(uint16_t usage) {
struct queue_item item;
item.queue_type = QTConsumer;
@@ -655,7 +659,7 @@ void adafruit_ble_send_consumer_key(uint16_t usage) {
}
#ifdef MOUSE_ENABLE
-void adafruit_ble_send_mouse_move(int8_t x, int8_t y, int8_t scroll, int8_t pan, uint8_t buttons) {
+void bluefruit_le_send_mouse_move(int8_t x, int8_t y, int8_t scroll, int8_t pan, uint8_t buttons) {
struct queue_item item;
item.queue_type = QTMouseMove;
@@ -671,9 +675,11 @@ void adafruit_ble_send_mouse_move(int8_t x, int8_t y, int8_t scroll, int8_t pan,
}
#endif
-uint32_t adafruit_ble_read_battery_voltage(void) { return state.vbat; }
+uint32_t bluefruit_le_read_battery_voltage(void) {
+ return state.vbat;
+}
-bool adafruit_ble_set_mode_leds(bool on) {
+bool bluefruit_le_set_mode_leds(bool on) {
if (!state.configured) {
return false;
}
@@ -689,7 +695,7 @@ bool adafruit_ble_set_mode_leds(bool on) {
}
// https://learn.adafruit.com/adafruit-feather-32u4-bluefruit-le/ble-generic#at-plus-blepowerlevel
-bool adafruit_ble_set_power_level(int8_t level) {
+bool bluefruit_le_set_power_level(int8_t level) {
char cmd[46];
if (!state.configured) {
return false;
diff --git a/drivers/bluetooth/adafruit_ble.h b/drivers/bluetooth/bluefruit_le.h
index b43e0771d9..de301c6167 100644
--- a/drivers/bluetooth/adafruit_ble.h
+++ b/drivers/bluetooth/bluefruit_le.h
@@ -16,43 +16,43 @@ extern "C" {
#endif
/* Instruct the module to enable HID keyboard support and reset */
-extern bool adafruit_ble_enable_keyboard(void);
+extern bool bluefruit_le_enable_keyboard(void);
/* Query to see if the BLE module is connected */
-extern bool adafruit_ble_query_is_connected(void);
+extern bool bluefruit_le_query_is_connected(void);
/* Returns true if we believe that the BLE module is connected.
* This uses our cached understanding that is maintained by
* calling ble_task() periodically. */
-extern bool adafruit_ble_is_connected(void);
+extern bool bluefruit_le_is_connected(void);
/* Call this periodically to process BLE-originated things */
-extern void adafruit_ble_task(void);
+extern void bluefruit_le_task(void);
/* Generates keypress events for a set of keys.
* The hid modifier mask specifies the state of the modifier keys for
* this set of keys.
* Also sends a key release indicator, so that the keys do not remain
* held down. */
-extern void adafruit_ble_send_keys(uint8_t hid_modifier_mask, uint8_t *keys, uint8_t nkeys);
+extern void bluefruit_le_send_keys(uint8_t hid_modifier_mask, uint8_t *keys, uint8_t nkeys);
/* Send a consumer usage.
* (milliseconds) */
-extern void adafruit_ble_send_consumer_key(uint16_t usage);
+extern void bluefruit_le_send_consumer_key(uint16_t usage);
#ifdef MOUSE_ENABLE
/* Send a mouse/wheel movement report.
* The parameters are signed and indicate positive or negative direction
* change. */
-extern void adafruit_ble_send_mouse_move(int8_t x, int8_t y, int8_t scroll, int8_t pan, uint8_t buttons);
+extern void bluefruit_le_send_mouse_move(int8_t x, int8_t y, int8_t scroll, int8_t pan, uint8_t buttons);
#endif
/* Compute battery voltage by reading an analog pin.
* Returns the integer number of millivolts */
-extern uint32_t adafruit_ble_read_battery_voltage(void);
+extern uint32_t bluefruit_le_read_battery_voltage(void);
-extern bool adafruit_ble_set_mode_leds(bool on);
-extern bool adafruit_ble_set_power_level(int8_t level);
+extern bool bluefruit_le_set_mode_leds(bool on);
+extern bool bluefruit_le_set_power_level(int8_t level);
#ifdef __cplusplus
}
diff --git a/drivers/bluetooth/outputselect.c b/drivers/bluetooth/outputselect.c
index f758c65280..b986ba274e 100644
--- a/drivers/bluetooth/outputselect.c
+++ b/drivers/bluetooth/outputselect.c
@@ -13,13 +13,10 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "outputselect.h"
+#include "usb_util.h"
-#if defined(PROTOCOL_LUFA)
-# include "lufa.h"
-#endif
-
-#ifdef MODULE_ADAFRUIT_BLE
-# include "adafruit_ble.h"
+#ifdef BLUETOOTH_BLUEFRUIT_LE
+# include "bluefruit_le.h"
#endif
uint8_t desired_output = OUTPUT_DEFAULT;
@@ -39,29 +36,23 @@ void set_output(uint8_t output) {
*/
__attribute__((weak)) void set_output_user(uint8_t output) {}
-static bool is_usb_configured(void) {
-#if defined(PROTOCOL_LUFA)
- return USB_DeviceState == DEVICE_STATE_Configured;
-#endif
-}
-
/** \brief Auto Detect Output
*
* FIXME: Needs doc
*/
uint8_t auto_detect_output(void) {
- if (is_usb_configured()) {
+ if (usb_connected_state()) {
return OUTPUT_USB;
}
-#ifdef MODULE_ADAFRUIT_BLE
- if (adafruit_ble_is_connected()) {
+#ifdef BLUETOOTH_BLUEFRUIT_LE
+ if (bluefruit_le_is_connected()) {
return OUTPUT_BLUETOOTH;
}
#endif
#ifdef BLUETOOTH_ENABLE
- return OUTPUT_BLUETOOTH; // should check if BT is connected here
+ return OUTPUT_BLUETOOTH; // should check if BT is connected here
#endif
return OUTPUT_NONE;
diff --git a/drivers/bluetooth/rn42.c b/drivers/bluetooth/rn42.c
new file mode 100644
index 0000000000..5d497cda20
--- /dev/null
+++ b/drivers/bluetooth/rn42.c
@@ -0,0 +1,101 @@
+/* Copyright 2021
+ *
+ * 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 2 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 "report.h"
+#include "uart.h"
+
+#ifndef RN42_BAUD_RATE
+# define RN42_BAUD_RATE 115200
+#endif
+
+// https://cdn.sparkfun.com/datasheets/Wireless/Bluetooth/bluetooth_cr_UG-v1.0r.pdf#G7.663734
+static inline uint16_t rn42_consumer_usage_to_bitmap(uint16_t usage) {
+ switch (usage) {
+ case AC_HOME:
+ return 0x0001;
+ case AL_EMAIL:
+ return 0x0002;
+ case AC_SEARCH:
+ return 0x0004;
+ case AL_KEYBOARD_LAYOUT:
+ return 0x0008;
+ case AUDIO_VOL_UP:
+ return 0x0010;
+ case AUDIO_VOL_DOWN:
+ return 0x0020;
+ case AUDIO_MUTE:
+ return 0x0040;
+ case TRANSPORT_PLAY_PAUSE:
+ return 0x0080;
+ case TRANSPORT_NEXT_TRACK:
+ return 0x0100;
+ case TRANSPORT_PREV_TRACK:
+ return 0x0200;
+ case TRANSPORT_STOP:
+ return 0x0400;
+ case TRANSPORT_EJECT:
+ return 0x0800;
+ case TRANSPORT_FAST_FORWARD:
+ return 0x1000;
+ case TRANSPORT_REWIND:
+ return 0x2000;
+ case TRANSPORT_STOP_EJECT:
+ return 0x4000;
+ case AL_LOCAL_BROWSER:
+ return 0x8000;
+ default:
+ return 0;
+ }
+}
+
+void rn42_init(void) {
+ uart_init(RN42_BAUD_RATE);
+}
+
+void rn42_send_keyboard(report_keyboard_t *report) {
+ uart_write(0xFD);
+ uart_write(0x09);
+ uart_write(0x01);
+ uart_write(report->mods);
+ uart_write(0x00);
+ for (uint8_t i = 0; i < KEYBOARD_REPORT_KEYS; i++) {
+ uart_write(report->keys[i]);
+ }
+}
+
+void rn42_send_mouse(report_mouse_t *report) {
+ uart_write(0xFD);
+ uart_write(0x00);
+ uart_write(0x03);
+ uart_write(report->buttons);
+ uart_write(report->x);
+ uart_write(report->y);
+ uart_write(report->v); // should try sending the wheel v here
+ uart_write(report->h); // should try sending the wheel h here
+ uart_write(0x00);
+}
+
+void rn42_send_consumer(uint16_t data) {
+ static uint16_t last_data = 0;
+ if (data == last_data) return;
+ last_data = data;
+ uint16_t bitmap = rn42_consumer_usage_to_bitmap(data);
+ uart_write(0xFD);
+ uart_write(0x03);
+ uart_write(0x03);
+ uart_write(bitmap & 0xFF);
+ uart_write((bitmap >> 8) & 0xFF);
+}
diff --git a/drivers/bluetooth/rn42.h b/drivers/bluetooth/rn42.h
new file mode 100644
index 0000000000..4747759111
--- /dev/null
+++ b/drivers/bluetooth/rn42.h
@@ -0,0 +1,25 @@
+/* Copyright 2021
+ *
+ * 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 2 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 "report.h"
+
+void rn42_init(void);
+
+void rn42_send_keyboard(report_keyboard_t *report);
+
+void rn42_send_mouse(report_mouse_t *report);
+
+void rn42_send_consumer(uint16_t data);
diff --git a/drivers/eeprom/eeprom_driver.c b/drivers/eeprom/eeprom_driver.c
index 6ce47faf7d..885cf21981 100644
--- a/drivers/eeprom/eeprom_driver.c
+++ b/drivers/eeprom/eeprom_driver.c
@@ -37,11 +37,17 @@ uint32_t eeprom_read_dword(const uint32_t *addr) {
return ret;
}
-void eeprom_write_byte(uint8_t *addr, uint8_t value) { eeprom_write_block(&value, addr, 1); }
+void eeprom_write_byte(uint8_t *addr, uint8_t value) {
+ eeprom_write_block(&value, addr, 1);
+}
-void eeprom_write_word(uint16_t *addr, uint16_t value) { eeprom_write_block(&value, addr, 2); }
+void eeprom_write_word(uint16_t *addr, uint16_t value) {
+ eeprom_write_block(&value, addr, 2);
+}
-void eeprom_write_dword(uint32_t *addr, uint32_t value) { eeprom_write_block(&value, addr, 4); }
+void eeprom_write_dword(uint32_t *addr, uint32_t value) {
+ eeprom_write_block(&value, addr, 4);
+}
void eeprom_update_block(const void *buf, void *addr, size_t len) {
uint8_t read_buf[len];
diff --git a/drivers/eeprom/eeprom_i2c.c b/drivers/eeprom/eeprom_i2c.c
index 8e80ff544f..a74a010415 100644
--- a/drivers/eeprom/eeprom_i2c.c
+++ b/drivers/eeprom/eeprom_i2c.c
@@ -43,7 +43,7 @@
#if defined(CONSOLE_ENABLE) && defined(DEBUG_EEPROM_OUTPUT)
# include "timer.h"
# include "debug.h"
-#endif // DEBUG_EEPROM_OUTPUT
+#endif // DEBUG_EEPROM_OUTPUT
static inline void fill_target_address(uint8_t *buffer, const void *addr) {
uintptr_t p = (uintptr_t)addr;
@@ -91,7 +91,7 @@ void eeprom_read_block(void *buf, const void *addr, size_t len) {
dprintf(" %02X", (int)(((uint8_t *)buf)[i]));
}
dprintf("\n");
-#endif // DEBUG_EEPROM_OUTPUT
+#endif // DEBUG_EEPROM_OUTPUT
}
void eeprom_write_block(const void *buf, void *addr, size_t len) {
@@ -122,7 +122,7 @@ void eeprom_write_block(const void *buf, void *addr, size_t len) {
dprintf(" %02X", (int)(read_buf[i]));
}
dprintf("\n");
-#endif // DEBUG_EEPROM_OUTPUT
+#endif // DEBUG_EEPROM_OUTPUT
i2c_transmit(EXTERNAL_EEPROM_I2C_ADDRESS((uintptr_t)addr), complete_packet, EXTERNAL_EEPROM_ADDRESS_SIZE + write_length, 100);
wait_ms(EXTERNAL_EEPROM_WRITE_TIME);
diff --git a/drivers/eeprom/eeprom_spi.c b/drivers/eeprom/eeprom_spi.c
index e273090854..25955498c4 100644
--- a/drivers/eeprom/eeprom_spi.c
+++ b/drivers/eeprom/eeprom_spi.c
@@ -52,7 +52,9 @@
# define EXTERNAL_EEPROM_SPI_TIMEOUT 100
#endif
-static bool spi_eeprom_start(void) { return spi_start(EXTERNAL_EEPROM_SPI_SLAVE_SELECT_PIN, EXTERNAL_EEPROM_SPI_LSBFIRST, EXTERNAL_EEPROM_SPI_MODE, EXTERNAL_EEPROM_SPI_CLOCK_DIVISOR); }
+static bool spi_eeprom_start(void) {
+ return spi_start(EXTERNAL_EEPROM_SPI_SLAVE_SELECT_PIN, EXTERNAL_EEPROM_SPI_LSBFIRST, EXTERNAL_EEPROM_SPI_MODE, EXTERNAL_EEPROM_SPI_CLOCK_DIVISOR);
+}
static spi_status_t spi_eeprom_wait_while_busy(int timeout) {
uint32_t deadline = timer_read32() + timeout;
@@ -80,7 +82,9 @@ static void spi_eeprom_transmit_address(uintptr_t addr) {
//----------------------------------------------------------------------------------------------------------------------
-void eeprom_driver_init(void) { spi_init(); }
+void eeprom_driver_init(void) {
+ spi_init();
+}
void eeprom_driver_erase(void) {
#if defined(CONSOLE_ENABLE) && defined(DEBUG_EEPROM_OUTPUT)
@@ -135,7 +139,7 @@ void eeprom_read_block(void *buf, const void *addr, size_t len) {
dprintf(" %02X", (int)(((uint8_t *)buf)[i]));
}
dprintf("\n");
-#endif // DEBUG_EEPROM_OUTPUT
+#endif // DEBUG_EEPROM_OUTPUT
spi_stop();
}
@@ -192,7 +196,7 @@ void eeprom_write_block(const void *buf, void *addr, size_t len) {
dprintf(" %02X", (int)(uint8_t)(read_buf[i]));
}
dprintf("\n");
-#endif // DEBUG_EEPROM_OUTPUT
+#endif // DEBUG_EEPROM_OUTPUT
spi_write(CMD_WRITE);
spi_eeprom_transmit_address(target_addr);
diff --git a/drivers/eeprom/eeprom_transient.c b/drivers/eeprom/eeprom_transient.c
index b4c78c6f40..9dc4289c27 100644
--- a/drivers/eeprom/eeprom_transient.c
+++ b/drivers/eeprom/eeprom_transient.c
@@ -30,9 +30,13 @@ size_t clamp_length(intptr_t offset, size_t len) {
return len;
}
-void eeprom_driver_init(void) { eeprom_driver_erase(); }
+void eeprom_driver_init(void) {
+ eeprom_driver_erase();
+}
-void eeprom_driver_erase(void) { memset(transientBuffer, 0x00, TRANSIENT_EEPROM_SIZE); }
+void eeprom_driver_erase(void) {
+ memset(transientBuffer, 0x00, TRANSIENT_EEPROM_SIZE);
+}
void eeprom_read_block(void *buf, const void *addr, size_t len) {
intptr_t offset = (intptr_t)addr;
diff --git a/drivers/eeprom/eeprom_transient.h b/drivers/eeprom/eeprom_transient.h
index d06189b246..687b8619fe 100644
--- a/drivers/eeprom/eeprom_transient.h
+++ b/drivers/eeprom/eeprom_transient.h
@@ -21,5 +21,5 @@
*/
#ifndef TRANSIENT_EEPROM_SIZE
# include "eeconfig.h"
-# define TRANSIENT_EEPROM_SIZE (((EECONFIG_SIZE + 3) / 4) * 4) // based off eeconfig's current usage, aligned to 4-byte sizes, to deal with LTO
+# define TRANSIENT_EEPROM_SIZE (((EECONFIG_SIZE + 3) / 4) * 4) // based off eeconfig's current usage, aligned to 4-byte sizes, to deal with LTO
#endif
diff --git a/drivers/flash/flash_spi.c b/drivers/flash/flash_spi.c
new file mode 100644
index 0000000000..f4cbf65159
--- /dev/null
+++ b/drivers/flash/flash_spi.c
@@ -0,0 +1,376 @@
+/*
+Copyright (C) 2021 Westberry Technology (ChangZhou) Corp., Ltd
+
+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 2 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 <string.h>
+
+#include "util.h"
+#include "wait.h"
+#include "debug.h"
+#include "timer.h"
+#include "flash_spi.h"
+#include "spi_master.h"
+
+/*
+ The time-out time of spi flash transmission.
+*/
+#ifndef EXTERNAL_FLASH_SPI_TIMEOUT
+# define EXTERNAL_FLASH_SPI_TIMEOUT 1000
+#endif
+
+/* ID comands */
+#define FLASH_CMD_RDID 0x9F /* RDID (Read Identification) */
+#define FLASH_CMD_RES 0xAB /* RES (Read Electronic ID) */
+#define FLASH_CMD_REMS 0x90 /* REMS (Read Electronic & Device ID) */
+
+/* register comands */
+#define FLASH_CMD_WRSR 0x01 /* WRSR (Write Status register) */
+#define FLASH_CMD_RDSR 0x05 /* RDSR (Read Status register) */
+
+/* READ comands */
+#define FLASH_CMD_READ 0x03 /* READ (1 x I/O) */
+#define FLASH_CMD_FASTREAD 0x0B /* FAST READ (Fast read data) */
+#define FLASH_CMD_DREAD 0x3B /* DREAD (1In/2 Out fast read) */
+
+/* Program comands */
+#define FLASH_CMD_WREN 0x06 /* WREN (Write Enable) */
+#define FLASH_CMD_WRDI 0x04 /* WRDI (Write Disable) */
+#define FLASH_CMD_PP 0x02 /* PP (page program) */
+
+/* Erase comands */
+#define FLASH_CMD_SE 0x20 /* SE (Sector Erase) */
+#define FLASH_CMD_BE 0xD8 /* BE (Block Erase) */
+#define FLASH_CMD_CE 0x60 /* CE (Chip Erase) hex code: 60 or C7 */
+
+/* Mode setting comands */
+#define FLASH_CMD_DP 0xB9 /* DP (Deep Power Down) */
+#define FLASH_CMD_RDP 0xAB /* RDP (Release form Deep Power Down) */
+
+/* Status register */
+#define FLASH_FLAG_WIP 0x01 /* Write in progress bit */
+#define FLASH_FLAG_WEL 0x02 /* Write enable latch bit */
+
+// #define DEBUG_FLASH_SPI_OUTPUT
+
+static bool spi_flash_start(void) {
+ return spi_start(EXTERNAL_FLASH_SPI_SLAVE_SELECT_PIN, EXTERNAL_FLASH_SPI_LSBFIRST, EXTERNAL_FLASH_SPI_MODE, EXTERNAL_FLASH_SPI_CLOCK_DIVISOR);
+}
+
+static flash_status_t spi_flash_wait_while_busy(void) {
+ uint32_t deadline = timer_read32() + EXTERNAL_FLASH_SPI_TIMEOUT;
+ flash_status_t response = FLASH_STATUS_SUCCESS;
+ uint8_t retval;
+
+ do {
+ bool res = spi_flash_start();
+ if (!res) {
+ dprint("Failed to start SPI! [spi flash wait while busy]\n");
+ return FLASH_STATUS_ERROR;
+ }
+
+ spi_write(FLASH_CMD_RDSR);
+
+ retval = (uint8_t)spi_read();
+
+ spi_stop();
+
+ if (timer_read32() >= deadline) {
+ response = FLASH_STATUS_TIMEOUT;
+ break;
+ }
+ } while (retval & FLASH_FLAG_WIP);
+
+ return response;
+}
+
+static flash_status_t spi_flash_write_enable(void) {
+ bool res = spi_flash_start();
+ if (!res) {
+ dprint("Failed to start SPI! [spi flash write enable]\n");
+ return FLASH_STATUS_ERROR;
+ }
+
+ spi_write(FLASH_CMD_WREN);
+
+ spi_stop();
+
+ return FLASH_STATUS_SUCCESS;
+}
+
+static flash_status_t spi_flash_write_disable(void) {
+ bool res = spi_flash_start();
+ if (!res) {
+ dprint("Failed to start SPI! [spi flash write disable]\n");
+ return FLASH_STATUS_ERROR;
+ }
+
+ spi_write(FLASH_CMD_WRDI);
+
+ spi_stop();
+
+ return FLASH_STATUS_SUCCESS;
+}
+
+/* This function is used for read transfer, write transfer and erase transfer. */
+static flash_status_t spi_flash_transaction(uint8_t cmd, uint32_t addr, uint8_t *data, size_t len) {
+ flash_status_t response = FLASH_STATUS_SUCCESS;
+ uint8_t buffer[EXTERNAL_FLASH_ADDRESS_SIZE + 1];
+
+ buffer[0] = cmd;
+ for (int i = 0; i < EXTERNAL_FLASH_ADDRESS_SIZE; ++i) {
+ buffer[EXTERNAL_FLASH_ADDRESS_SIZE - i] = addr & 0xFF;
+ addr >>= 8;
+ }
+
+ bool res = spi_flash_start();
+ if (!res) {
+ dprint("Failed to start SPI! [spi flash transmit]\n");
+ return FLASH_STATUS_ERROR;
+ }
+
+ response = spi_transmit(buffer, sizeof(buffer));
+
+ if ((!response) && (data != NULL)) {
+ switch (cmd) {
+ case FLASH_CMD_READ:
+ response = spi_receive(data, len);
+ break;
+ case FLASH_CMD_PP:
+ response = spi_transmit(data, len);
+ break;
+ default:
+ response = FLASH_STATUS_ERROR;
+ break;
+ }
+ }
+
+ spi_stop();
+
+ return response;
+}
+
+void flash_init(void) {
+ spi_init();
+}
+
+flash_status_t flash_erase_chip(void) {
+ flash_status_t response = FLASH_STATUS_SUCCESS;
+
+ /* Wait for the write-in-progress bit to be cleared. */
+ response = spi_flash_wait_while_busy();
+ if (response != FLASH_STATUS_SUCCESS) {
+ dprint("Failed to check WIP flag! [spi flash erase chip]\n");
+ return response;
+ }
+
+ /* Enable writes. */
+ response = spi_flash_write_enable();
+ if (response != FLASH_STATUS_SUCCESS) {
+ dprint("Failed to write-enable! [spi flash erase chip]\n");
+ return response;
+ }
+
+ /* Erase Chip. */
+ bool res = spi_flash_start();
+ if (!res) {
+ dprint("Failed to start SPI! [spi flash erase chip]\n");
+ return FLASH_STATUS_ERROR;
+ }
+ spi_write(FLASH_CMD_CE);
+ spi_stop();
+
+ /* Wait for the write-in-progress bit to be cleared.*/
+ response = spi_flash_wait_while_busy();
+ if (response != FLASH_STATUS_SUCCESS) {
+ dprint("Failed to check WIP flag! [spi flash erase chip]\n");
+ return response;
+ }
+
+ return response;
+}
+
+flash_status_t flash_erase_sector(uint32_t addr) {
+ flash_status_t response = FLASH_STATUS_SUCCESS;
+
+ /* Check that the address exceeds the limit. */
+ if ((addr + (EXTERNAL_FLASH_SECTOR_SIZE)) >= (EXTERNAL_FLASH_SIZE) || ((addr % (EXTERNAL_FLASH_SECTOR_SIZE)) != 0)) {
+ dprintf("Flash erase sector address over limit! [addr:0x%x]\n", (uint32_t)addr);
+ return FLASH_STATUS_ERROR;
+ }
+
+ /* Wait for the write-in-progress bit to be cleared. */
+ response = spi_flash_wait_while_busy();
+ if (response != FLASH_STATUS_SUCCESS) {
+ dprint("Failed to check WIP flag! [spi flash erase sector]\n");
+ return response;
+ }
+
+ /* Enable writes. */
+ response = spi_flash_write_enable();
+ if (response != FLASH_STATUS_SUCCESS) {
+ dprint("Failed to write-enable! [spi flash erase sector]\n");
+ return response;
+ }
+
+ /* Erase Sector. */
+ response = spi_flash_transaction(FLASH_CMD_SE, addr, NULL, 0);
+ if (response != FLASH_STATUS_SUCCESS) {
+ dprint("Failed to erase sector! [spi flash erase sector]\n");
+ return response;
+ }
+
+ /* Wait for the write-in-progress bit to be cleared.*/
+ response = spi_flash_wait_while_busy();
+ if (response != FLASH_STATUS_SUCCESS) {
+ dprint("Failed to check WIP flag! [spi flash erase sector]\n");
+ return response;
+ }
+
+ return response;
+}
+
+flash_status_t flash_erase_block(uint32_t addr) {
+ flash_status_t response = FLASH_STATUS_SUCCESS;
+
+ /* Check that the address exceeds the limit. */
+ if ((addr + (EXTERNAL_FLASH_BLOCK_SIZE)) >= (EXTERNAL_FLASH_SIZE) || ((addr % (EXTERNAL_FLASH_BLOCK_SIZE)) != 0)) {
+ dprintf("Flash erase block address over limit! [addr:0x%x]\n", (uint32_t)addr);
+ return FLASH_STATUS_ERROR;
+ }
+
+ /* Wait for the write-in-progress bit to be cleared. */
+ response = spi_flash_wait_while_busy();
+ if (response != FLASH_STATUS_SUCCESS) {
+ dprint("Failed to check WIP flag! [spi flash erase block]\n");
+ return response;
+ }
+
+ /* Enable writes. */
+ response = spi_flash_write_enable();
+ if (response != FLASH_STATUS_SUCCESS) {
+ dprint("Failed to write-enable! [spi flash erase block]\n");
+ return response;
+ }
+
+ /* Erase Block. */
+ response = spi_flash_transaction(FLASH_CMD_BE, addr, NULL, 0);
+ if (response != FLASH_STATUS_SUCCESS) {
+ dprint("Failed to erase block! [spi flash erase block]\n");
+ return response;
+ }
+
+ /* Wait for the write-in-progress bit to be cleared.*/
+ response = spi_flash_wait_while_busy();
+ if (response != FLASH_STATUS_SUCCESS) {
+ dprint("Failed to check WIP flag! [spi flash erase block]\n");
+ return response;
+ }
+
+ return response;
+}
+
+flash_status_t flash_read_block(uint32_t addr, void *buf, size_t len) {
+ flash_status_t response = FLASH_STATUS_SUCCESS;
+ uint8_t * read_buf = (uint8_t *)buf;
+
+ /* Wait for the write-in-progress bit to be cleared. */
+ response = spi_flash_wait_while_busy();
+ if (response != FLASH_STATUS_SUCCESS) {
+ dprint("Failed to check WIP flag! [spi flash read block]\n");
+ memset(read_buf, 0, len);
+ return response;
+ }
+
+ /* Perform read. */
+ response = spi_flash_transaction(FLASH_CMD_READ, addr, read_buf, len);
+ if (response != FLASH_STATUS_SUCCESS) {
+ dprint("Failed to read block! [spi flash read block]\n");
+ memset(read_buf, 0, len);
+ return response;
+ }
+
+#if defined(CONSOLE_ENABLE) && defined(DEBUG_FLASH_SPI_OUTPUT)
+ dprintf("[SPI FLASH R] 0x%08lX: ", addr);
+ for (size_t i = 0; i < len; ++i) {
+ dprintf(" %02X", (int)(((uint8_t *)read_buf)[i]));
+ }
+ dprintf("\n");
+#endif // DEBUG_FLASH_SPI_OUTPUT
+
+ return response;
+}
+
+flash_status_t flash_write_block(uint32_t addr, const void *buf, size_t len) {
+ flash_status_t response = FLASH_STATUS_SUCCESS;
+ uint8_t * write_buf = (uint8_t *)buf;
+
+ while (len > 0) {
+ uint32_t page_offset = addr % EXTERNAL_FLASH_PAGE_SIZE;
+ size_t write_length = EXTERNAL_FLASH_PAGE_SIZE - page_offset;
+ if (write_length > len) {
+ write_length = len;
+ }
+
+ /* Wait for the write-in-progress bit to be cleared. */
+ response = spi_flash_wait_while_busy();
+ if (response != FLASH_STATUS_SUCCESS) {
+ dprint("Failed to check WIP flag! [spi flash write block]\n");
+ return response;
+ }
+
+ /* Enable writes. */
+ response = spi_flash_write_enable();
+ if (response != FLASH_STATUS_SUCCESS) {
+ dprint("Failed to write-enable! [spi flash write block]\n");
+ return response;
+ }
+
+#if defined(CONSOLE_ENABLE) && defined(DEBUG_FLASH_SPI_OUTPUT)
+ dprintf("[SPI FLASH W] 0x%08lX: ", addr);
+ for (size_t i = 0; i < write_length; i++) {
+ dprintf(" %02X", (int)(uint8_t)(write_buf[i]));
+ }
+ dprintf("\n");
+#endif // DEBUG_FLASH_SPI_OUTPUT
+
+ /* Perform the write. */
+ response = spi_flash_transaction(FLASH_CMD_PP, addr, write_buf, write_length);
+ if (response != FLASH_STATUS_SUCCESS) {
+ dprint("Failed to write block! [spi flash write block]\n");
+ return response;
+ }
+
+ write_buf += write_length;
+ addr += write_length;
+ len -= write_length;
+ }
+
+ /* Wait for the write-in-progress bit to be cleared. */
+ response = spi_flash_wait_while_busy();
+ if (response != FLASH_STATUS_SUCCESS) {
+ dprint("Failed to check WIP flag! [spi flash write block]\n");
+ return response;
+ }
+
+ /* Disable writes. */
+ response = spi_flash_write_disable();
+ if (response != FLASH_STATUS_SUCCESS) {
+ dprint("Failed to write-disable! [spi flash write block]\n");
+ return response;
+ }
+
+ return response;
+}
diff --git a/drivers/flash/flash_spi.h b/drivers/flash/flash_spi.h
new file mode 100644
index 0000000000..abe95e955e
--- /dev/null
+++ b/drivers/flash/flash_spi.h
@@ -0,0 +1,136 @@
+/*
+Copyright (C) 2021 Westberry Technology (ChangZhou) Corp., Ltd
+
+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 2 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/>.
+*/
+
+#pragma once
+
+/* All the following default configurations are based on MX25L4006E Nor FLASH. */
+
+/*
+ The slave select pin of the FLASH.
+ This needs to be a normal GPIO pin_t value, such as B14.
+*/
+#ifndef EXTERNAL_FLASH_SPI_SLAVE_SELECT_PIN
+# error "No chip select pin defined -- missing EXTERNAL_FLASH_SPI_SLAVE_SELECT_PIN"
+#endif
+
+/*
+ The clock divisor for SPI to ensure that the MCU is within the
+ specifications of the FLASH chip. Generally this will be PCLK divided by
+ the intended divisor -- check your clock settings and the datasheet of
+ your FLASH.
+*/
+#ifndef EXTERNAL_FLASH_SPI_CLOCK_DIVISOR
+# ifdef __AVR__
+# define EXTERNAL_FLASH_SPI_CLOCK_DIVISOR 4
+# else
+# define EXTERNAL_FLASH_SPI_CLOCK_DIVISOR 8
+# endif
+#endif
+
+/*
+ The SPI mode to communicate with the FLASH.
+*/
+#ifndef EXTERNAL_FLASH_SPI_MODE
+# define EXTERNAL_FLASH_SPI_MODE 0
+#endif
+
+/*
+ Whether or not the SPI communication between the MCU and FLASH should be
+ LSB-first.
+*/
+#ifndef EXTERNAL_FLASH_SPI_LSBFIRST
+# define EXTERNAL_FLASH_SPI_LSBFIRST false
+#endif
+
+/*
+ The Flash address size in bytes, as specified in datasheet.
+*/
+#ifndef EXTERNAL_FLASH_ADDRESS_SIZE
+# define EXTERNAL_FLASH_ADDRESS_SIZE 3
+#endif
+
+/*
+ The page size of the FLASH in bytes, as specified in the datasheet.
+*/
+#ifndef EXTERNAL_FLASH_PAGE_SIZE
+# define EXTERNAL_FLASH_PAGE_SIZE 256
+#endif
+
+/*
+ The sector size of the FLASH in bytes, as specified in the datasheet.
+*/
+#ifndef EXTERNAL_FLASH_SECTOR_SIZE
+# define EXTERNAL_FLASH_SECTOR_SIZE (4 * 1024)
+#endif
+
+/*
+ The block size of the FLASH in bytes, as specified in the datasheet.
+*/
+#ifndef EXTERNAL_FLASH_BLOCK_SIZE
+# define EXTERNAL_FLASH_BLOCK_SIZE (64 * 1024)
+#endif
+
+/*
+ The total size of the FLASH in bytes, as specified in the datasheet.
+*/
+#ifndef EXTERNAL_FLASH_SIZE
+# define EXTERNAL_FLASH_SIZE (512 * 1024)
+#endif
+
+/*
+ The block count of the FLASH, calculated by total FLASH size and block size.
+*/
+#define EXTERNAL_FLASH_BLOCK_COUNT ((EXTERNAL_FLASH_SIZE) / (EXTERNAL_FLASH_BLOCK_SIZE))
+
+/*
+ The sector count of the FLASH, calculated by total FLASH size and sector size.
+*/
+#define EXTERNAL_FLASH_SECTOR_COUNT ((EXTERNAL_FLASH_SIZE) / (EXTERNAL_FLASH_SECTOR_SIZE))
+
+/*
+ The page count of the FLASH, calculated by total FLASH size and page size.
+*/
+#define EXTERNAL_FLASH_PAGE_COUNT ((EXTERNAL_FLASH_SIZE) / (EXTERNAL_FLASH_PAGE_SIZE))
+
+typedef int16_t flash_status_t;
+
+#define FLASH_STATUS_SUCCESS (0)
+#define FLASH_STATUS_ERROR (-1)
+#define FLASH_STATUS_TIMEOUT (-2)
+#define FLASH_STATUS_BAD_ADDRESS (-3)
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#include <stdint.h>
+
+void flash_init(void);
+
+flash_status_t flash_erase_chip(void);
+
+flash_status_t flash_erase_block(uint32_t addr);
+
+flash_status_t flash_erase_sector(uint32_t addr);
+
+flash_status_t flash_read_block(uint32_t addr, void *buf, size_t len);
+
+flash_status_t flash_write_block(uint32_t addr, const void *buf, size_t len);
+
+#ifdef __cplusplus
+}
+#endif
diff --git a/drivers/gpio/mcp23018.c b/drivers/gpio/mcp23018.c
new file mode 100644
index 0000000000..41cbfe087e
--- /dev/null
+++ b/drivers/gpio/mcp23018.c
@@ -0,0 +1,108 @@
+// Copyright 2022 zvecr<git@zvecr.com>
+// SPDX-License-Identifier: GPL-2.0-or-later
+
+#include "mcp23018.h"
+#include "i2c_master.h"
+#include "wait.h"
+#include "debug.h"
+
+#define SLAVE_TO_ADDR(n) (n << 1)
+#define TIMEOUT 100
+
+enum {
+ CMD_IODIRA = 0x00, // i/o direction register
+ CMD_IODIRB = 0x01,
+ CMD_GPPUA = 0x0C, // GPIO pull-up resistor register
+ CMD_GPPUB = 0x0D,
+ CMD_GPIOA = 0x12, // general purpose i/o port register (write modifies OLAT)
+ CMD_GPIOB = 0x13,
+};
+
+void mcp23018_init(uint8_t addr) {
+ static uint8_t s_init = 0;
+ if (!s_init) {
+ i2c_init();
+ wait_ms(1000);
+
+ s_init = 1;
+ }
+}
+
+bool mcp23018_set_config(uint8_t slave_addr, mcp23018_port_t port, uint8_t conf) {
+ uint8_t addr = SLAVE_TO_ADDR(slave_addr);
+ uint8_t cmdDirection = port ? CMD_IODIRB : CMD_IODIRA;
+ uint8_t cmdPullup = port ? CMD_GPPUB : CMD_GPPUA;
+
+ i2c_status_t ret = i2c_writeReg(addr, cmdDirection, &conf, sizeof(conf), TIMEOUT);
+ if (ret != I2C_STATUS_SUCCESS) {
+ dprintf("mcp23018_set_config::directionFAILED::%u\n", ret);
+ return false;
+ }
+
+ ret = i2c_writeReg(addr, cmdPullup, &conf, sizeof(conf), TIMEOUT);
+ if (ret != I2C_STATUS_SUCCESS) {
+ dprintf("mcp23018_set_config::pullupFAILED::%u\n", ret);
+ return false;
+ }
+
+ return true;
+}
+
+bool mcp23018_set_output(uint8_t slave_addr, mcp23018_port_t port, uint8_t conf) {
+ uint8_t addr = SLAVE_TO_ADDR(slave_addr);
+ uint8_t cmd = port ? CMD_GPIOB : CMD_GPIOA;
+
+ i2c_status_t ret = i2c_writeReg(addr, cmd, &conf, sizeof(conf), TIMEOUT);
+ if (ret != I2C_STATUS_SUCCESS) {
+ dprintf("mcp23018_set_output::FAILED::%u\n", ret);
+ return false;
+ }
+
+ return true;
+}
+
+bool mcp23018_set_output_all(uint8_t slave_addr, uint8_t confA, uint8_t confB) {
+ uint8_t addr = SLAVE_TO_ADDR(slave_addr);
+ uint8_t conf[2] = {confA, confB};
+
+ i2c_status_t ret = i2c_writeReg(addr, CMD_GPIOA, &conf[0], sizeof(conf), TIMEOUT);
+ if (ret != I2C_STATUS_SUCCESS) {
+ dprintf("mcp23018_set_output::FAILED::%u\n", ret);
+ return false;
+ }
+
+ return true;
+}
+
+bool mcp23018_readPins(uint8_t slave_addr, mcp23018_port_t port, uint8_t* out) {
+ uint8_t addr = SLAVE_TO_ADDR(slave_addr);
+ uint8_t cmd = port ? CMD_GPIOB : CMD_GPIOA;
+
+ i2c_status_t ret = i2c_readReg(addr, cmd, out, sizeof(uint8_t), TIMEOUT);
+ if (ret != I2C_STATUS_SUCCESS) {
+ dprintf("mcp23018_readPins::FAILED::%u\n", ret);
+ return false;
+ }
+
+ return true;
+}
+
+bool mcp23018_readPins_all(uint8_t slave_addr, uint16_t* out) {
+ uint8_t addr = SLAVE_TO_ADDR(slave_addr);
+
+ typedef union {
+ uint8_t u8[2];
+ uint16_t u16;
+ } data16;
+
+ data16 data = {.u16 = 0};
+
+ i2c_status_t ret = i2c_readReg(addr, CMD_GPIOA, &data.u8[0], sizeof(data), TIMEOUT);
+ if (ret != I2C_STATUS_SUCCESS) {
+ dprintf("mcp23018_readPins::FAILED::%u\n", ret);
+ return false;
+ }
+
+ *out = data.u16;
+ return true;
+}
diff --git a/drivers/gpio/mcp23018.h b/drivers/gpio/mcp23018.h
new file mode 100644
index 0000000000..e7c2730dd1
--- /dev/null
+++ b/drivers/gpio/mcp23018.h
@@ -0,0 +1,65 @@
+// Copyright 2022 zvecr<git@zvecr.com>
+// SPDX-License-Identifier: GPL-2.0-or-later
+
+#pragma once
+
+#include <stdint.h>
+#include <stdbool.h>
+
+/**
+ * Port ID
+ */
+typedef enum {
+ mcp23018_PORTA,
+ mcp23018_PORTB,
+} mcp23018_port_t;
+
+/**
+ * Helpers for set_config
+ */
+enum {
+ ALL_OUTPUT = 0,
+ ALL_INPUT = 0xFF,
+};
+
+/**
+ * Helpers for set_output
+ */
+enum {
+ ALL_LOW = 0,
+ ALL_HIGH = 0xFF,
+};
+
+/**
+ * Init expander and any other dependent drivers
+ */
+void mcp23018_init(uint8_t slave_addr);
+
+/**
+ * Configure input/output to a given port
+ */
+bool mcp23018_set_config(uint8_t slave_addr, mcp23018_port_t port, uint8_t conf);
+
+/**
+ * Write high/low to a given port
+ */
+bool mcp23018_set_output(uint8_t slave_addr, mcp23018_port_t port, uint8_t conf);
+
+/**
+ * Write high/low to both ports sequentially
+ *
+ * - slightly faster than multiple set_output
+ */
+bool mcp23018_set_output_all(uint8_t slave_addr, uint8_t confA, uint8_t confB);
+
+/**
+ * Read state of a given port
+ */
+bool mcp23018_readPins(uint8_t slave_addr, mcp23018_port_t port, uint8_t* ret);
+
+/**
+ * Read state of both ports sequentially
+ *
+ * - slightly faster than multiple readPins
+ */
+bool mcp23018_readPins_all(uint8_t slave_addr, uint16_t* ret);
diff --git a/drivers/gpio/pca9555.c b/drivers/gpio/pca9555.c
index 02b5abbdde..adcd040083 100644
--- a/drivers/gpio/pca9555.c
+++ b/drivers/gpio/pca9555.c
@@ -1,18 +1,6 @@
-/* Copyright 2019
- *
- * 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 2 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/>.
- */
+// Copyright 2020 zvecr<git@zvecr.com>
+// SPDX-License-Identifier: GPL-2.0-or-later
+
#include "i2c_master.h"
#include "pca9555.h"
@@ -45,39 +33,59 @@ void pca9555_init(uint8_t slave_addr) {
// i2c_stop();
}
-void pca9555_set_config(uint8_t slave_addr, uint8_t port, uint8_t conf) {
+bool pca9555_set_config(uint8_t slave_addr, pca9555_port_t port, uint8_t conf) {
uint8_t addr = SLAVE_TO_ADDR(slave_addr);
uint8_t cmd = port ? CMD_CONFIG_1 : CMD_CONFIG_0;
i2c_status_t ret = i2c_writeReg(addr, cmd, &conf, sizeof(conf), TIMEOUT);
if (ret != I2C_STATUS_SUCCESS) {
print("pca9555_set_config::FAILED\n");
+ return false;
}
+
+ return true;
}
-void pca9555_set_output(uint8_t slave_addr, uint8_t port, uint8_t conf) {
+bool pca9555_set_output(uint8_t slave_addr, pca9555_port_t port, uint8_t conf) {
uint8_t addr = SLAVE_TO_ADDR(slave_addr);
uint8_t cmd = port ? CMD_OUTPUT_1 : CMD_OUTPUT_0;
i2c_status_t ret = i2c_writeReg(addr, cmd, &conf, sizeof(conf), TIMEOUT);
if (ret != I2C_STATUS_SUCCESS) {
print("pca9555_set_output::FAILED\n");
+ return false;
}
+
+ return true;
}
-uint8_t pca9555_readPins(uint8_t slave_addr, uint8_t port) {
+bool pca9555_set_output_all(uint8_t slave_addr, uint8_t confA, uint8_t confB) {
+ uint8_t addr = SLAVE_TO_ADDR(slave_addr);
+ uint8_t conf[2] = {confA, confB};
+
+ i2c_status_t ret = i2c_writeReg(addr, CMD_OUTPUT_0, &conf[0], sizeof(conf), TIMEOUT);
+ if (ret != I2C_STATUS_SUCCESS) {
+ dprintf("pca9555_set_output::FAILED::%u\n", ret);
+ return false;
+ }
+
+ return true;
+}
+
+bool pca9555_readPins(uint8_t slave_addr, pca9555_port_t port, uint8_t* out) {
uint8_t addr = SLAVE_TO_ADDR(slave_addr);
uint8_t cmd = port ? CMD_INPUT_1 : CMD_INPUT_0;
- uint8_t data = 0;
- i2c_status_t ret = i2c_readReg(addr, cmd, &data, sizeof(data), TIMEOUT);
+ i2c_status_t ret = i2c_readReg(addr, cmd, out, sizeof(uint8_t), TIMEOUT);
if (ret != I2C_STATUS_SUCCESS) {
print("pca9555_readPins::FAILED\n");
+ return false;
}
- return data;
+
+ return true;
}
-uint16_t pca9555_readAllPins(uint8_t slave_addr) {
+bool pca9555_readPins_all(uint8_t slave_addr, uint16_t* out) {
uint8_t addr = SLAVE_TO_ADDR(slave_addr);
typedef union {
@@ -85,11 +93,14 @@ uint16_t pca9555_readAllPins(uint8_t slave_addr) {
uint16_t u16;
} data16;
- data16 data;
+ data16 data = {.u16 = 0};
i2c_status_t ret = i2c_readReg(addr, CMD_INPUT_0, &data.u8[0], sizeof(data), TIMEOUT);
if (ret != I2C_STATUS_SUCCESS) {
- print("pca9555_readAllPins::FAILED\n");
+ print("pca9555_readPins_all::FAILED\n");
+ return false;
}
- return data.u16;
+
+ *out = data.u16;
+ return true;
}
diff --git a/drivers/gpio/pca9555.h b/drivers/gpio/pca9555.h
index 3341ec3eb5..6362ab68ae 100644
--- a/drivers/gpio/pca9555.h
+++ b/drivers/gpio/pca9555.h
@@ -1,20 +1,11 @@
-/* Copyright 2019
- *
- * 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 2 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/>.
- */
+// Copyright 2020 zvecr<git@zvecr.com>
+// SPDX-License-Identifier: GPL-2.0-or-later
+
#pragma once
+#include <stdint.h>
+#include <stdbool.h>
+
/*
PCA9555
,----------.
@@ -38,20 +29,60 @@
`----------'
*/
-#define PCA9555_PORT0 0
-#define PCA9555_PORT1 1
+/**
+ * Port ID
+ */
+typedef enum {
+ PCA9555_PORT0,
+ PCA9555_PORT1,
+} pca9555_port_t;
-#define ALL_OUTPUT 0
-#define ALL_INPUT 0xFF
-#define ALL_LOW 0
-#define ALL_HIGH 0xFF
+/**
+ * Helpers for set_config
+ */
+enum {
+ ALL_OUTPUT = 0,
+ ALL_INPUT = 0xFF,
+};
+
+/**
+ * Helpers for set_output
+ */
+enum {
+ ALL_LOW = 0,
+ ALL_HIGH = 0xFF,
+};
+/**
+ * Init expander and any other dependent drivers
+ */
void pca9555_init(uint8_t slave_addr);
-void pca9555_set_config(uint8_t slave_addr, uint8_t port, uint8_t conf);
+/**
+ * Configure input/output to a given port
+ */
+bool pca9555_set_config(uint8_t slave_addr, pca9555_port_t port, uint8_t conf);
-void pca9555_set_output(uint8_t slave_addr, uint8_t port, uint8_t conf);
+/**
+ * Write high/low to a given port
+ */
+bool pca9555_set_output(uint8_t slave_addr, pca9555_port_t port, uint8_t conf);
-uint8_t pca9555_readPins(uint8_t slave_addr, uint8_t port);
+/**
+ * Write high/low to both ports sequentially
+ *
+ * - slightly faster than multiple set_output
+ */
+bool pca9555_set_output_all(uint8_t slave_addr, uint8_t confA, uint8_t confB);
-uint16_t pca9555_readAllPins(uint8_t slave_addr);
+/**
+ * Read state of a given port
+ */
+bool pca9555_readPins(uint8_t slave_addr, pca9555_port_t port, uint8_t* ret);
+
+/**
+ * Read state of both ports sequentially
+ *
+ * - slightly faster than multiple readPins
+ */
+bool pca9555_readPins_all(uint8_t slave_addr, uint16_t* ret);
diff --git a/drivers/gpio/sn74x138.c b/drivers/gpio/sn74x138.c
new file mode 100644
index 0000000000..222e5db56c
--- /dev/null
+++ b/drivers/gpio/sn74x138.c
@@ -0,0 +1,65 @@
+/* Copyright 2022
+ *
+ * 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 2 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 "sn74x138.h"
+#include "gpio.h"
+
+#define ADDRESS_PIN_COUNT 3
+
+#ifndef SN74X138_ADDRESS_PINS
+# error sn74x138: no address pins defined!
+#endif
+
+static const pin_t address_pins[ADDRESS_PIN_COUNT] = SN74X138_ADDRESS_PINS;
+
+void sn74x138_init(void) {
+ for (int i = 0; i < ADDRESS_PIN_COUNT; i++) {
+ setPinOutput(address_pins[i]);
+ writePinLow(address_pins[i]);
+ }
+
+#if defined(SN74X138_E1_PIN)
+ setPinOutput(SN74X138_E1_PIN);
+ writePinHigh(SN74X138_E1_PIN);
+#endif
+
+#if defined(SN74X138_E2_PIN)
+ setPinOutput(SN74X138_E2_PIN);
+ writePinHigh(SN74X138_E2_PIN);
+#endif
+#if defined(SN74X138_E3_PIN)
+ setPinOutput(SN74X138_E3_PIN);
+ writePinLow(SN74X138_E3_PIN);
+#endif
+}
+
+void sn74x138_set_enabled(bool enabled) {
+#if defined(SN74X138_E1_PIN)
+ writePin(SN74X138_E1_PIN, !enabled);
+#endif
+#if defined(SN74X138_E2_PIN)
+ writePin(SN74X138_E2_PIN, !enabled);
+#endif
+#if defined(SN74X138_E3_PIN)
+ writePin(SN74X138_E3_PIN, enabled);
+#endif
+}
+
+void sn74x138_set_addr(uint8_t address) {
+ for (int i = 0; i < ADDRESS_PIN_COUNT; i++) {
+ writePin(address_pins[i], address & (1 << i));
+ }
+}
diff --git a/drivers/gpio/sn74x138.h b/drivers/gpio/sn74x138.h
new file mode 100644
index 0000000000..6f1f20e618
--- /dev/null
+++ b/drivers/gpio/sn74x138.h
@@ -0,0 +1,48 @@
+/* Copyright 2022
+ *
+ * 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 2 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/>.
+ */
+
+#pragma once
+
+#include <stdint.h>
+#include <stdbool.h>
+
+/**
+ * Driver for 74x138 3-to-8 decoder/demultiplexer with inverting outputs
+ * https://assets.nexperia.com/documents/data-sheet/74HC_HCT138.pdf
+ */
+
+/**
+ * Initialize the address and output enable pins.
+ */
+void sn74x138_init(void);
+
+/**
+ * Set the enabled state.
+ *
+ * When enabled is true, pulls the E1 and E2 pins low, and the E3 pin high.
+ *
+ * \param enabled The enable state to set.
+ */
+void sn74x138_set_enabled(bool enabled);
+
+/**
+ * Set the output pin address.
+ *
+ * The selected output pin will be pulled low, while the remaining output pins will be high.
+ *
+ * \param address The address to set, from 0 to 7.
+ */
+void sn74x138_set_addr(uint8_t address);
diff --git a/drivers/haptic/DRV2605L.c b/drivers/haptic/DRV2605L.c
index 5de2b354c9..5a1d2ca0af 100644
--- a/drivers/haptic/DRV2605L.c
+++ b/drivers/haptic/DRV2605L.c
@@ -106,12 +106,14 @@ void DRV_init(void) {
void DRV_rtp_init(void) {
DRV_write(DRV_GO, 0x00);
- DRV_write(DRV_RTP_INPUT, 20); // 20 is the lowest value I've found where haptics can still be felt.
+ DRV_write(DRV_RTP_INPUT, 20); // 20 is the lowest value I've found where haptics can still be felt.
DRV_write(DRV_MODE, 0x05);
DRV_write(DRV_GO, 0x01);
}
-void DRV_amplitude(uint8_t amplitude) { DRV_write(DRV_RTP_INPUT, amplitude); }
+void DRV_amplitude(uint8_t amplitude) {
+ DRV_write(DRV_RTP_INPUT, amplitude);
+}
void DRV_pulse(uint8_t sequence) {
DRV_write(DRV_GO, 0x00);
diff --git a/drivers/haptic/solenoid.c b/drivers/haptic/solenoid.c
index 7a09940f78..14d868bffe 100644
--- a/drivers/haptic/solenoid.c
+++ b/drivers/haptic/solenoid.c
@@ -28,13 +28,21 @@ uint8_t solenoid_dwell = SOLENOID_DEFAULT_DWELL;
extern haptic_config_t haptic_config;
-void solenoid_buzz_on(void) { haptic_set_buzz(1); }
+void solenoid_buzz_on(void) {
+ haptic_set_buzz(1);
+}
-void solenoid_buzz_off(void) { haptic_set_buzz(0); }
+void solenoid_buzz_off(void) {
+ haptic_set_buzz(0);
+}
-void solenoid_set_buzz(int buzz) { haptic_set_buzz(buzz); }
+void solenoid_set_buzz(int buzz) {
+ haptic_set_buzz(buzz);
+}
-void solenoid_set_dwell(uint8_t dwell) { solenoid_dwell = dwell; }
+void solenoid_set_dwell(uint8_t dwell) {
+ solenoid_dwell = dwell;
+}
void solenoid_stop(void) {
SOLENOID_PIN_WRITE_INACTIVE();
@@ -89,4 +97,6 @@ void solenoid_setup(void) {
}
}
-void solenoid_shutdown(void) { SOLENOID_PIN_WRITE_INACTIVE(); }
+void solenoid_shutdown(void) {
+ SOLENOID_PIN_WRITE_INACTIVE();
+}
diff --git a/drivers/lcd/st7565.c b/drivers/lcd/st7565.c
index 49b13c00f1..47ee02804b 100644
--- a/drivers/lcd/st7565.c
+++ b/drivers/lcd/st7565.c
@@ -39,7 +39,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
// Addressing Setting Commands
#define PAM_SETCOLUMN_LSB 0x00
#define PAM_SETCOLUMN_MSB 0x10
-#define PAM_PAGE_ADDR 0xB0 // 0xb0 -- 0xb7
+#define PAM_PAGE_ADDR 0xB0 // 0xb0 -- 0xb7
// Hardware Configuration Commands
#define DISPLAY_START_LINE 0x40
@@ -138,7 +138,9 @@ bool st7565_init(display_rotation_t rotation) {
return true;
}
-__attribute__((weak)) display_rotation_t st7565_init_user(display_rotation_t rotation) { return rotation; }
+__attribute__((weak)) display_rotation_t st7565_init_user(display_rotation_t rotation) {
+ return rotation;
+}
void st7565_clear(void) {
memset(st7565_buffer, 0, sizeof(st7565_buffer));
@@ -212,7 +214,8 @@ void st7565_advance_page(bool clearPageRemainder) {
remaining = remaining / ST7565_FONT_WIDTH;
// Write empty character until next line
- while (remaining--) st7565_write_char(' ', false);
+ while (remaining--)
+ st7565_write_char(' ', false);
} else {
// Next page index out of bounds?
if (index + remaining >= ST7565_MATRIX_SIZE) {
@@ -263,7 +266,7 @@ void st7565_write_char(const char data, bool invert) {
_Static_assert(sizeof(font) >= ((ST7565_FONT_END + 1 - ST7565_FONT_START) * ST7565_FONT_WIDTH), "ST7565_FONT_END references outside array");
// set the reder buffer data
- uint8_t cast_data = (uint8_t)data; // font based on unsigned type for index
+ uint8_t cast_data = (uint8_t)data; // font based on unsigned type for index
if (cast_data < ST7565_FONT_START || cast_data > ST7565_FONT_END) {
memset(st7565_cursor, 0x00, ST7565_FONT_WIDTH);
} else {
@@ -389,7 +392,7 @@ void st7565_write_raw_P(const char *data, uint16_t size) {
st7565_dirty |= ((ST7565_BLOCK_TYPE)1 << (i / ST7565_BLOCK_SIZE));
}
}
-#endif // defined(__AVR__)
+#endif // defined(__AVR__)
bool st7565_on(void) {
if (!st7565_initialized) {
@@ -429,7 +432,9 @@ bool st7565_off(void) {
__attribute__((weak)) void st7565_off_user(void) {}
-bool st7565_is_on(void) { return st7565_active; }
+bool st7565_is_on(void) {
+ return st7565_active;
+}
bool st7565_invert(bool invert) {
if (!st7565_initialized) {
@@ -445,9 +450,13 @@ bool st7565_invert(bool invert) {
return st7565_inverted;
}
-uint8_t st7565_max_chars(void) { return ST7565_DISPLAY_WIDTH / ST7565_FONT_WIDTH; }
+uint8_t st7565_max_chars(void) {
+ return ST7565_DISPLAY_WIDTH / ST7565_FONT_WIDTH;
+}
-uint8_t st7565_max_lines(void) { return ST7565_DISPLAY_HEIGHT / ST7565_FONT_HEIGHT; }
+uint8_t st7565_max_lines(void) {
+ return ST7565_DISPLAY_HEIGHT / ST7565_FONT_HEIGHT;
+}
void st7565_task(void) {
if (!st7565_initialized) {
diff --git a/drivers/lcd/st7565.h b/drivers/lcd/st7565.h
index d453dbe6da..0e42c8765b 100644
--- a/drivers/lcd/st7565.h
+++ b/drivers/lcd/st7565.h
@@ -29,16 +29,16 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
# define ST7565_DISPLAY_HEIGHT 32
#endif
#ifndef ST7565_MATRIX_SIZE
-# define ST7565_MATRIX_SIZE (ST7565_DISPLAY_HEIGHT / 8 * ST7565_DISPLAY_WIDTH) // 1024 (compile time mathed)
+# define ST7565_MATRIX_SIZE (ST7565_DISPLAY_HEIGHT / 8 * ST7565_DISPLAY_WIDTH) // 1024 (compile time mathed)
#endif
#ifndef ST7565_BLOCK_TYPE
# define ST7565_BLOCK_TYPE uint16_t
#endif
#ifndef ST7565_BLOCK_COUNT
-# define ST7565_BLOCK_COUNT (sizeof(ST7565_BLOCK_TYPE) * 8) // 32 (compile time mathed)
+# define ST7565_BLOCK_COUNT (sizeof(ST7565_BLOCK_TYPE) * 8) // 32 (compile time mathed)
#endif
#ifndef ST7565_BLOCK_SIZE
-# define ST7565_BLOCK_SIZE (ST7565_MATRIX_SIZE / ST7565_BLOCK_COUNT) // 32 (compile time mathed)
+# define ST7565_BLOCK_SIZE (ST7565_MATRIX_SIZE / ST7565_BLOCK_COUNT) // 32 (compile time mathed)
#endif
// the column address corresponding to the first column in the display hardware
@@ -174,7 +174,7 @@ void st7565_write_raw_P(const char *data, uint16_t size);
# define st7565_write_P(data, invert) st7565_write(data, invert)
# define st7565_write_ln_P(data, invert) st7565_write_ln(data, invert)
# define st7565_write_raw_P(data, size) st7565_write_raw(data, size)
-#endif // defined(__AVR__)
+#endif // defined(__AVR__)
// Can be used to manually turn on the screen if it is off
// Returns true if the screen was on or turns on
diff --git a/drivers/led/apa102.c b/drivers/led/apa102.c
index 00e7eb4505..f291948975 100644
--- a/drivers/led/apa102.c
+++ b/drivers/led/apa102.c
@@ -20,15 +20,15 @@
#ifndef APA102_NOPS
# if defined(__AVR__)
-# define APA102_NOPS 0 // AVR at 16 MHz already spends 62.5 ns per clock, so no extra delay is needed
+# define APA102_NOPS 0 // AVR at 16 MHz already spends 62.5 ns per clock, so no extra delay is needed
# elif defined(PROTOCOL_CHIBIOS)
# include "hal.h"
# if defined(STM32F0XX) || defined(STM32F1XX) || defined(STM32F3XX) || defined(STM32F4XX) || defined(STM32L0XX) || defined(GD32VF103)
-# define APA102_NOPS (100 / (1000000000L / (CPU_CLOCK / 4))) // This calculates how many loops of 4 nops to run to delay 100 ns
+# define APA102_NOPS (100 / (1000000000L / (CPU_CLOCK / 4))) // This calculates how many loops of 4 nops to run to delay 100 ns
# else
# error("APA102_NOPS configuration required")
-# define APA102_NOPS 0 // this just pleases the compile so the above error is easier to spot
+# define APA102_NOPS 0 // this just pleases the compile so the above error is easier to spot
# endif
# endif
#endif
@@ -72,7 +72,9 @@ void apa102_setleds(LED_TYPE *start_led, uint16_t num_leds) {
}
// Overwrite the default rgblight_call_driver to use apa102 driver
-void rgblight_call_driver(LED_TYPE *start_led, uint8_t num_leds) { apa102_setleds(start_led, num_leds); }
+void rgblight_call_driver(LED_TYPE *start_led, uint8_t num_leds) {
+ apa102_setleds(start_led, num_leds);
+}
void static apa102_init(void) {
setPinOutput(RGB_DI_PIN);
diff --git a/drivers/led/aw20216.c b/drivers/led/aw20216.c
index 2c7ff8f088..59389cdcd6 100644
--- a/drivers/led/aw20216.c
+++ b/drivers/led/aw20216.c
@@ -23,17 +23,17 @@
*/
#define AWINIC_ID 0b1010 << 4
-#define AW_PAGE_FUNCTION 0x00 << 1 // PG0, Function registers
-#define AW_PAGE_PWM 0x01 << 1 // PG1, LED PWM control
-#define AW_PAGE_SCALING 0x02 << 1 // PG2, LED current scaling control
-#define AW_PAGE_PATCHOICE 0x03 << 1 // PG3, Pattern choice?
-#define AW_PAGE_PWMSCALING 0x04 << 1 // PG4, LED PWM + Scaling control?
+#define AW_PAGE_FUNCTION 0x00 << 1 // PG0, Function registers
+#define AW_PAGE_PWM 0x01 << 1 // PG1, LED PWM control
+#define AW_PAGE_SCALING 0x02 << 1 // PG2, LED current scaling control
+#define AW_PAGE_PATCHOICE 0x03 << 1 // PG3, Pattern choice?
+#define AW_PAGE_PWMSCALING 0x04 << 1 // PG4, LED PWM + Scaling control?
#define AW_WRITE 0
#define AW_READ 1
-#define AW_REG_CONFIGURATION 0x00 // PG0
-#define AW_REG_GLOBALCURRENT 0x01 // PG0
+#define AW_REG_CONFIGURATION 0x00 // PG0
+#define AW_REG_GLOBALCURRENT 0x01 // PG0
// Default value of AW_REG_CONFIGURATION
// D7:D4 = 1011, SWSEL (SW1~SW12 active)
diff --git a/drivers/led/ckled2001.c b/drivers/led/ckled2001.c
index 990e50cb60..8d71805a24 100644
--- a/drivers/led/ckled2001.c
+++ b/drivers/led/ckled2001.c
@@ -125,7 +125,16 @@ void CKLED2001_init(uint8_t addr) {
// Set CURRENT PAGE (Page 4)
CKLED2001_write_register(addr, CONFIGURE_CMD_PAGE, CURRENT_TUNE_PAGE);
for (int i = 0; i < LED_CURRENT_TUNE_LENGTH; i++) {
- CKLED2001_write_register(addr, i, 0xFF);
+ switch (i) {
+ case 2:
+ case 5:
+ case 8:
+ case 11:
+ CKLED2001_write_register(addr, i, 0xA0);
+ break;
+ default:
+ CKLED2001_write_register(addr, i, 0xFF);
+ }
}
// Enable LEDs ON/OFF
diff --git a/drivers/led/issi/is31fl3731-simple.c b/drivers/led/issi/is31fl3731-simple.c
index f51e2e38af..3abe9ea337 100644
--- a/drivers/led/issi/is31fl3731-simple.c
+++ b/drivers/led/issi/is31fl3731-simple.c
@@ -42,13 +42,13 @@
#define ISSI_REG_PICTUREFRAME 0x01
// Not defined in the datasheet -- See AN for IC
-#define ISSI_REG_GHOST_IMAGE_PREVENTION 0xC2 // Set bit 4 to enable de-ghosting
+#define ISSI_REG_GHOST_IMAGE_PREVENTION 0xC2 // Set bit 4 to enable de-ghosting
#define ISSI_REG_SHUTDOWN 0x0A
#define ISSI_REG_AUDIOSYNC 0x06
#define ISSI_COMMANDREGISTER 0xFD
-#define ISSI_BANK_FUNCTIONREG 0x0B // helpfully called 'page nine'
+#define ISSI_BANK_FUNCTIONREG 0x0B // helpfully called 'page nine'
#ifndef ISSI_TIMEOUT
# define ISSI_TIMEOUT 100
@@ -148,7 +148,7 @@ void IS31FL3731_init(uint8_t addr) {
// enable software shutdown
IS31FL3731_write_register(addr, ISSI_REG_SHUTDOWN, 0x00);
-#ifdef ISSI_3731_DEGHOST // set to enable de-ghosting of the array
+#ifdef ISSI_3731_DEGHOST // set to enable de-ghosting of the array
IS31FL3731_write_register(addr, ISSI_REG_GHOST_IMAGE_PREVENTION, 0x10);
#endif
diff --git a/drivers/led/issi/is31fl3731.c b/drivers/led/issi/is31fl3731.c
index e6190a6b90..9c6c29f081 100644
--- a/drivers/led/issi/is31fl3731.c
+++ b/drivers/led/issi/is31fl3731.c
@@ -41,13 +41,13 @@
#define ISSI_REG_PICTUREFRAME 0x01
// Not defined in the datasheet -- See AN for IC
-#define ISSI_REG_GHOST_IMAGE_PREVENTION 0xC2 // Set bit 4 to enable de-ghosting
+#define ISSI_REG_GHOST_IMAGE_PREVENTION 0xC2 // Set bit 4 to enable de-ghosting
#define ISSI_REG_SHUTDOWN 0x0A
#define ISSI_REG_AUDIOSYNC 0x06
#define ISSI_COMMANDREGISTER 0xFD
-#define ISSI_BANK_FUNCTIONREG 0x0B // helpfully called 'page nine'
+#define ISSI_BANK_FUNCTIONREG 0x0B // helpfully called 'page nine'
#ifndef ISSI_TIMEOUT
# define ISSI_TIMEOUT 100
@@ -136,7 +136,7 @@ void IS31FL3731_init(uint8_t addr) {
// enable software shutdown
IS31FL3731_write_register(addr, ISSI_REG_SHUTDOWN, 0x00);
-#ifdef ISSI_3731_DEGHOST // set to enable de-ghosting of the array
+#ifdef ISSI_3731_DEGHOST // set to enable de-ghosting of the array
IS31FL3731_write_register(addr, ISSI_REG_GHOST_IMAGE_PREVENTION, 0x10);
#endif
diff --git a/drivers/led/issi/is31fl3733-simple.c b/drivers/led/issi/is31fl3733-simple.c
new file mode 100644
index 0000000000..af006f756d
--- /dev/null
+++ b/drivers/led/issi/is31fl3733-simple.c
@@ -0,0 +1,248 @@
+/* Copyright 2017 Jason Williams
+ * Copyright 2018 Jack Humbert
+ * Copyright 2018 Yiancar
+ * Copyright 2021 Doni Crosby
+ * Copyright 2021 Leo Deng
+ *
+ * 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 2 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 "is31fl3733-simple.h"
+#include "i2c_master.h"
+#include "wait.h"
+
+// This is a 7-bit address, that gets left-shifted and bit 0
+// set to 0 for write, 1 for read (as per I2C protocol)
+// The address will vary depending on your wiring:
+// 00 <-> GND
+// 01 <-> SCL
+// 10 <-> SDA
+// 11 <-> VCC
+// ADDR1 represents A1:A0 of the 7-bit address.
+// ADDR2 represents A3:A2 of the 7-bit address.
+// The result is: 0b101(ADDR2)(ADDR1)
+#define ISSI_ADDR_DEFAULT 0x50
+
+#define ISSI_COMMANDREGISTER 0xFD
+#define ISSI_COMMANDREGISTER_WRITELOCK 0xFE
+#define ISSI_INTERRUPTMASKREGISTER 0xF0
+#define ISSI_INTERRUPTSTATUSREGISTER 0xF1
+
+#define ISSI_PAGE_LEDCONTROL 0x00 // PG0
+#define ISSI_PAGE_PWM 0x01 // PG1
+#define ISSI_PAGE_AUTOBREATH 0x02 // PG2
+#define ISSI_PAGE_FUNCTION 0x03 // PG3
+
+#define ISSI_REG_CONFIGURATION 0x00 // PG3
+#define ISSI_REG_GLOBALCURRENT 0x01 // PG3
+#define ISSI_REG_RESET 0x11 // PG3
+#define ISSI_REG_SWPULLUP 0x0F // PG3
+#define ISSI_REG_CSPULLUP 0x10 // PG3
+
+#ifndef ISSI_TIMEOUT
+# define ISSI_TIMEOUT 100
+#endif
+
+#ifndef ISSI_PERSISTENCE
+# define ISSI_PERSISTENCE 0
+#endif
+
+#ifndef ISSI_PWM_FREQUENCY
+# define ISSI_PWM_FREQUENCY 0b000 // PFS - IS31FL3733B only
+#endif
+
+#ifndef ISSI_SWPULLUP
+# define ISSI_SWPULLUP PUR_0R
+#endif
+
+#ifndef ISSI_CSPULLUP
+# define ISSI_CSPULLUP PUR_0R
+#endif
+
+// Transfer buffer for TWITransmitData()
+uint8_t g_twi_transfer_buffer[20];
+
+// These buffers match the IS31FL3733 PWM registers.
+// The control buffers match the PG0 LED On/Off registers.
+// Storing them like this is optimal for I2C transfers to the registers.
+// We could optimize this and take out the unused registers from these
+// buffers and the transfers in IS31FL3733_write_pwm_buffer() but it's
+// probably not worth the extra complexity.
+uint8_t g_pwm_buffer[LED_DRIVER_COUNT][192];
+bool g_pwm_buffer_update_required[LED_DRIVER_COUNT] = {false};
+
+/* There's probably a better way to init this... */
+#if LED_DRIVER_COUNT == 1
+uint8_t g_led_control_registers[LED_DRIVER_COUNT][24] = {{0}};
+#elif LED_DRIVER_COUNT == 2
+uint8_t g_led_control_registers[LED_DRIVER_COUNT][24] = {{0}, {0}};
+#elif LED_DRIVER_COUNT == 3
+uint8_t g_led_control_registers[LED_DRIVER_COUNT][24] = {{0}, {0}, {0}};
+#elif LED_DRIVER_COUNT == 4
+uint8_t g_led_control_registers[LED_DRIVER_COUNT][24] = {{0}, {0}, {0}, {0}};
+#endif
+bool g_led_control_registers_update_required[LED_DRIVER_COUNT] = {false};
+
+bool IS31FL3733_write_register(uint8_t addr, uint8_t reg, uint8_t data) {
+ // If the transaction fails function returns false.
+ g_twi_transfer_buffer[0] = reg;
+ g_twi_transfer_buffer[1] = data;
+
+#if ISSI_PERSISTENCE > 0
+ for (uint8_t i = 0; i < ISSI_PERSISTENCE; i++) {
+ if (i2c_transmit(addr << 1, g_twi_transfer_buffer, 2, ISSI_TIMEOUT) != 0) {
+ return false;
+ }
+ }
+#else
+ if (i2c_transmit(addr << 1, g_twi_transfer_buffer, 2, ISSI_TIMEOUT) != 0) {
+ return false;
+ }
+#endif
+ return true;
+}
+
+bool IS31FL3733_write_pwm_buffer(uint8_t addr, uint8_t *pwm_buffer) {
+ // Assumes PG1 is already selected.
+ // If any of the transactions fails function returns false.
+ // Transmit PWM registers in 12 transfers of 16 bytes.
+ // g_twi_transfer_buffer[] is 20 bytes
+
+ // Iterate over the pwm_buffer contents at 16 byte intervals.
+ for (int i = 0; i < 192; i += 16) {
+ g_twi_transfer_buffer[0] = i;
+ // Copy the data from i to i+15.
+ // Device will auto-increment register for data after the first byte
+ // Thus this sets registers 0x00-0x0F, 0x10-0x1F, etc. in one transfer.
+ for (int j = 0; j < 16; j++) {
+ g_twi_transfer_buffer[1 + j] = pwm_buffer[i + j];
+ }
+
+#if ISSI_PERSISTENCE > 0
+ for (uint8_t i = 0; i < ISSI_PERSISTENCE; i++) {
+ if (i2c_transmit(addr << 1, g_twi_transfer_buffer, 17, ISSI_TIMEOUT) != 0) {
+ return false;
+ }
+ }
+#else
+ if (i2c_transmit(addr << 1, g_twi_transfer_buffer, 17, ISSI_TIMEOUT) != 0) {
+ return false;
+ }
+#endif
+ }
+ return true;
+}
+
+void IS31FL3733_init(uint8_t addr, uint8_t sync) {
+ // In order to avoid the LEDs being driven with garbage data
+ // in the LED driver's PWM registers, shutdown is enabled last.
+ // Set up the mode and other settings, clear the PWM registers,
+ // then disable software shutdown.
+ // Sync is passed so set it according to the datasheet.
+
+ // Unlock the command register.
+ IS31FL3733_write_register(addr, ISSI_COMMANDREGISTER_WRITELOCK, 0xC5);
+
+ // Select PG0
+ IS31FL3733_write_register(addr, ISSI_COMMANDREGISTER, ISSI_PAGE_LEDCONTROL);
+ // Turn off all LEDs.
+ for (int i = 0x00; i <= 0x17; i++) {
+ IS31FL3733_write_register(addr, i, 0x00);
+ }
+
+ // Unlock the command register.
+ IS31FL3733_write_register(addr, ISSI_COMMANDREGISTER_WRITELOCK, 0xC5);
+
+ // Select PG1
+ IS31FL3733_write_register(addr, ISSI_COMMANDREGISTER, ISSI_PAGE_PWM);
+ // Set PWM on all LEDs to 0
+ // No need to setup Breath registers to PWM as that is the default.
+ for (int i = 0x00; i <= 0xBF; i++) {
+ IS31FL3733_write_register(addr, i, 0x00);
+ }
+
+ // Unlock the command register.
+ IS31FL3733_write_register(addr, ISSI_COMMANDREGISTER_WRITELOCK, 0xC5);
+
+ // Select PG3
+ IS31FL3733_write_register(addr, ISSI_COMMANDREGISTER, ISSI_PAGE_FUNCTION);
+ // Set de-ghost pull-up resistors (SWx)
+ IS31FL3733_write_register(addr, ISSI_REG_SWPULLUP, ISSI_SWPULLUP);
+ // Set de-ghost pull-down resistors (CSx)
+ IS31FL3733_write_register(addr, ISSI_REG_CSPULLUP, ISSI_CSPULLUP);
+ // Set global current to maximum.
+ IS31FL3733_write_register(addr, ISSI_REG_GLOBALCURRENT, 0xFF);
+ // Disable software shutdown.
+ IS31FL3733_write_register(addr, ISSI_REG_CONFIGURATION, ((sync & 0b11) << 6) | ((ISSI_PWM_FREQUENCY & 0b111) << 3) | 0x01);
+
+ // Wait 10ms to ensure the device has woken up.
+ wait_ms(10);
+}
+
+void IS31FL3733_set_value(int index, uint8_t value) {
+ if (index >= 0 && index < DRIVER_LED_TOTAL) {
+ is31_led led = g_is31_leds[index];
+
+ g_pwm_buffer[led.driver][led.v] = value;
+ g_pwm_buffer_update_required[led.driver] = true;
+ }
+}
+
+void IS31FL3733_set_value_all(uint8_t value) {
+ for (int i = 0; i < DRIVER_LED_TOTAL; i++) {
+ IS31FL3733_set_value(i, value);
+ }
+}
+
+void IS31FL3733_set_led_control_register(uint8_t index, bool value) {
+ is31_led led = g_is31_leds[index];
+
+ uint8_t control_register = led.v / 8;
+ uint8_t bit_value = led.v % 8;
+
+ if (value) {
+ g_led_control_registers[led.driver][control_register] |= (1 << bit_value);
+ } else {
+ g_led_control_registers[led.driver][control_register] &= ~(1 << bit_value);
+ }
+
+ g_led_control_registers_update_required[led.driver] = true;
+}
+
+void IS31FL3733_update_pwm_buffers(uint8_t addr, uint8_t index) {
+ if (g_pwm_buffer_update_required[index]) {
+ // Firstly we need to unlock the command register and select PG1.
+ IS31FL3733_write_register(addr, ISSI_COMMANDREGISTER_WRITELOCK, 0xC5);
+ IS31FL3733_write_register(addr, ISSI_COMMANDREGISTER, ISSI_PAGE_PWM);
+
+ // If any of the transactions fail we risk writing dirty PG0,
+ // refresh page 0 just in case.
+ if (!IS31FL3733_write_pwm_buffer(addr, g_pwm_buffer[index])) {
+ g_led_control_registers_update_required[index] = true;
+ }
+ g_pwm_buffer_update_required[index] = false;
+ }
+}
+
+void IS31FL3733_update_led_control_registers(uint8_t addr, uint8_t index) {
+ if (g_led_control_registers_update_required[index]) {
+ // Firstly we need to unlock the command register and select PG0
+ IS31FL3733_write_register(addr, ISSI_COMMANDREGISTER_WRITELOCK, 0xC5);
+ IS31FL3733_write_register(addr, ISSI_COMMANDREGISTER, ISSI_PAGE_LEDCONTROL);
+ for (int i = 0; i < 24; i++) {
+ IS31FL3733_write_register(addr, i, g_led_control_registers[index][i]);
+ }
+ g_led_control_registers_update_required[index] = false;
+ }
+}
diff --git a/drivers/led/issi/is31fl3733-simple.h b/drivers/led/issi/is31fl3733-simple.h
new file mode 100644
index 0000000000..f5253e3101
--- /dev/null
+++ b/drivers/led/issi/is31fl3733-simple.h
@@ -0,0 +1,260 @@
+/* Copyright 2017 Jason Williams
+ * Copyright 2018 Jack Humbert
+ * Copyright 2018 Yiancar
+ * Copyright 2021 Doni Crosby
+ * Copyright 2021 Leo Deng
+ *
+ * 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 2 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/>.
+ */
+
+#pragma once
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "progmem.h"
+
+typedef struct is31_led {
+ uint8_t driver : 2;
+ uint8_t v;
+} __attribute__((packed)) is31_led;
+
+extern const is31_led __flash g_is31_leds[DRIVER_LED_TOTAL];
+
+void IS31FL3733_init(uint8_t addr, uint8_t sync);
+bool IS31FL3733_write_register(uint8_t addr, uint8_t reg, uint8_t data);
+bool IS31FL3733_write_pwm_buffer(uint8_t addr, uint8_t *pwm_buffer);
+
+void IS31FL3733_set_value(int index, uint8_t value);
+void IS31FL3733_set_value_all(uint8_t value);
+
+void IS31FL3733_set_led_control_register(uint8_t index, bool value);
+
+// This should not be called from an interrupt
+// (eg. from a timer interrupt).
+// Call this while idle (in between matrix scans).
+// If the buffer is dirty, it will update the driver with the buffer.
+void IS31FL3733_update_pwm_buffers(uint8_t addr, uint8_t index);
+void IS31FL3733_update_led_control_registers(uint8_t addr, uint8_t index);
+
+#define PUR_0R 0x00 // No PUR resistor
+#define PUR_05KR 0x02 // 0.5k Ohm resistor in t_NOL
+#define PUR_3KR 0x03 // 3.0k Ohm resistor on all the time
+#define PUR_4KR 0x04 // 4.0k Ohm resistor on all the time
+#define PUR_8KR 0x05 // 8.0k Ohm resistor on all the time
+#define PUR_16KR 0x06 // 16k Ohm resistor on all the time
+#define PUR_32KR 0x07 // 32k Ohm resistor in t_NOL
+
+#define A_1 0x00
+#define A_2 0x01
+#define A_3 0x02
+#define A_4 0x03
+#define A_5 0x04
+#define A_6 0x05
+#define A_7 0x06
+#define A_8 0x07
+#define A_9 0x08
+#define A_10 0x09
+#define A_11 0x0A
+#define A_12 0x0B
+#define A_13 0x0C
+#define A_14 0x0D
+#define A_15 0x0E
+#define A_16 0x0F
+
+#define B_1 0x10
+#define B_2 0x11
+#define B_3 0x12
+#define B_4 0x13
+#define B_5 0x14
+#define B_6 0x15
+#define B_7 0x16
+#define B_8 0x17
+#define B_9 0x18
+#define B_10 0x19
+#define B_11 0x1A
+#define B_12 0x1B
+#define B_13 0x1C
+#define B_14 0x1D
+#define B_15 0x1E
+#define B_16 0x1F
+
+#define C_1 0x20
+#define C_2 0x21
+#define C_3 0x22
+#define C_4 0x23
+#define C_5 0x24
+#define C_6 0x25
+#define C_7 0x26
+#define C_8 0x27
+#define C_9 0x28
+#define C_10 0x29
+#define C_11 0x2A
+#define C_12 0x2B
+#define C_13 0x2C
+#define C_14 0x2D
+#define C_15 0x2E
+#define C_16 0x2F
+
+#define D_1 0x30
+#define D_2 0x31
+#define D_3 0x32
+#define D_4 0x33
+#define D_5 0x34
+#define D_6 0x35
+#define D_7 0x36
+#define D_8 0x37
+#define D_9 0x38
+#define D_10 0x39
+#define D_11 0x3A
+#define D_12 0x3B
+#define D_13 0x3C
+#define D_14 0x3D
+#define D_15 0x3E
+#define D_16 0x3F
+
+#define E_1 0x40
+#define E_2 0x41
+#define E_3 0x42
+#define E_4 0x43
+#define E_5 0x44
+#define E_6 0x45
+#define E_7 0x46
+#define E_8 0x47
+#define E_9 0x48
+#define E_10 0x49
+#define E_11 0x4A
+#define E_12 0x4B
+#define E_13 0x4C
+#define E_14 0x4D
+#define E_15 0x4E
+#define E_16 0x4F
+
+#define F_1 0x50
+#define F_2 0x51
+#define F_3 0x52
+#define F_4 0x53
+#define F_5 0x54
+#define F_6 0x55
+#define F_7 0x56
+#define F_8 0x57
+#define F_9 0x58
+#define F_10 0x59
+#define F_11 0x5A
+#define F_12 0x5B
+#define F_13 0x5C
+#define F_14 0x5D
+#define F_15 0x5E
+#define F_16 0x5F
+
+#define G_1 0x60
+#define G_2 0x61
+#define G_3 0x62
+#define G_4 0x63
+#define G_5 0x64
+#define G_6 0x65
+#define G_7 0x66
+#define G_8 0x67
+#define G_9 0x68
+#define G_10 0x69
+#define G_11 0x6A
+#define G_12 0x6B
+#define G_13 0x6C
+#define G_14 0x6D
+#define G_15 0x6E
+#define G_16 0x6F
+
+#define H_1 0x70
+#define H_2 0x71
+#define H_3 0x72
+#define H_4 0x73
+#define H_5 0x74
+#define H_6 0x75
+#define H_7 0x76
+#define H_8 0x77
+#define H_9 0x78
+#define H_10 0x79
+#define H_11 0x7A
+#define H_12 0x7B
+#define H_13 0x7C
+#define H_14 0x7D
+#define H_15 0x7E
+#define H_16 0x7F
+
+#define I_1 0x80
+#define I_2 0x81
+#define I_3 0x82
+#define I_4 0x83
+#define I_5 0x84
+#define I_6 0x85
+#define I_7 0x86
+#define I_8 0x87
+#define I_9 0x88
+#define I_10 0x89
+#define I_11 0x8A
+#define I_12 0x8B
+#define I_13 0x8C
+#define I_14 0x8D
+#define I_15 0x8E
+#define I_16 0x8F
+
+#define J_1 0x90
+#define J_2 0x91
+#define J_3 0x92
+#define J_4 0x93
+#define J_5 0x94
+#define J_6 0x95
+#define J_7 0x96
+#define J_8 0x97
+#define J_9 0x98
+#define J_10 0x99
+#define J_11 0x9A
+#define J_12 0x9B
+#define J_13 0x9C
+#define J_14 0x9D
+#define J_15 0x9E
+#define J_16 0x9F
+
+#define K_1 0xA0
+#define K_2 0xA1
+#define K_3 0xA2
+#define K_4 0xA3
+#define K_5 0xA4
+#define K_6 0xA5
+#define K_7 0xA6
+#define K_8 0xA7
+#define K_9 0xA8
+#define K_10 0xA9
+#define K_11 0xAA
+#define K_12 0xAB
+#define K_13 0xAC
+#define K_14 0xAD
+#define K_15 0xAE
+#define K_16 0xAF
+
+#define L_1 0xB0
+#define L_2 0xB1
+#define L_3 0xB2
+#define L_4 0xB3
+#define L_5 0xB4
+#define L_6 0xB5
+#define L_7 0xB6
+#define L_8 0xB7
+#define L_9 0xB8
+#define L_10 0xB9
+#define L_11 0xBA
+#define L_12 0xBB
+#define L_13 0xBC
+#define L_14 0xBD
+#define L_15 0xBE
+#define L_16 0xBF
diff --git a/drivers/led/issi/is31fl3733.c b/drivers/led/issi/is31fl3733.c
index 696491d070..a2fdaa90fa 100644
--- a/drivers/led/issi/is31fl3733.c
+++ b/drivers/led/issi/is31fl3733.c
@@ -38,16 +38,16 @@
#define ISSI_INTERRUPTMASKREGISTER 0xF0
#define ISSI_INTERRUPTSTATUSREGISTER 0xF1
-#define ISSI_PAGE_LEDCONTROL 0x00 // PG0
-#define ISSI_PAGE_PWM 0x01 // PG1
-#define ISSI_PAGE_AUTOBREATH 0x02 // PG2
-#define ISSI_PAGE_FUNCTION 0x03 // PG3
+#define ISSI_PAGE_LEDCONTROL 0x00 // PG0
+#define ISSI_PAGE_PWM 0x01 // PG1
+#define ISSI_PAGE_AUTOBREATH 0x02 // PG2
+#define ISSI_PAGE_FUNCTION 0x03 // PG3
-#define ISSI_REG_CONFIGURATION 0x00 // PG3
-#define ISSI_REG_GLOBALCURRENT 0x01 // PG3
-#define ISSI_REG_RESET 0x11 // PG3
-#define ISSI_REG_SWPULLUP 0x0F // PG3
-#define ISSI_REG_CSPULLUP 0x10 // PG3
+#define ISSI_REG_CONFIGURATION 0x00 // PG3
+#define ISSI_REG_GLOBALCURRENT 0x01 // PG3
+#define ISSI_REG_RESET 0x11 // PG3
+#define ISSI_REG_SWPULLUP 0x0F // PG3
+#define ISSI_REG_CSPULLUP 0x10 // PG3
#ifndef ISSI_TIMEOUT
# define ISSI_TIMEOUT 100
@@ -58,7 +58,7 @@
#endif
#ifndef ISSI_PWM_FREQUENCY
-# define ISSI_PWM_FREQUENCY 0b000 // PFS - IS31FL3733B only
+# define ISSI_PWM_FREQUENCY 0b000 // PFS - IS31FL3733B only
#endif
#ifndef ISSI_SWPULLUP
diff --git a/drivers/led/issi/is31fl3733.h b/drivers/led/issi/is31fl3733.h
index c5d62fed85..7653dd17c0 100644
--- a/drivers/led/issi/is31fl3733.h
+++ b/drivers/led/issi/is31fl3733.h
@@ -48,13 +48,13 @@ void IS31FL3733_set_led_control_register(uint8_t index, bool red, bool green, bo
void IS31FL3733_update_pwm_buffers(uint8_t addr, uint8_t index);
void IS31FL3733_update_led_control_registers(uint8_t addr, uint8_t index);
-#define PUR_0R 0x00 // No PUR resistor
-#define PUR_05KR 0x02 // 0.5k Ohm resistor in t_NOL
-#define PUR_3KR 0x03 // 3.0k Ohm resistor on all the time
-#define PUR_4KR 0x04 // 4.0k Ohm resistor on all the time
-#define PUR_8KR 0x05 // 8.0k Ohm resistor on all the time
-#define PUR_16KR 0x06 // 16k Ohm resistor on all the time
-#define PUR_32KR 0x07 // 32k Ohm resistor in t_NOL
+#define PUR_0R 0x00 // No PUR resistor
+#define PUR_05KR 0x02 // 0.5k Ohm resistor in t_NOL
+#define PUR_3KR 0x03 // 3.0k Ohm resistor on all the time
+#define PUR_4KR 0x04 // 4.0k Ohm resistor on all the time
+#define PUR_8KR 0x05 // 8.0k Ohm resistor on all the time
+#define PUR_16KR 0x06 // 16k Ohm resistor on all the time
+#define PUR_32KR 0x07 // 32k Ohm resistor in t_NOL
#define A_1 0x00
#define A_2 0x01
diff --git a/drivers/led/issi/is31fl3736.c b/drivers/led/issi/is31fl3736.c
index c9a871118d..7752a3f6cb 100644
--- a/drivers/led/issi/is31fl3736.c
+++ b/drivers/led/issi/is31fl3736.c
@@ -36,16 +36,16 @@
#define ISSI_INTERRUPTMASKREGISTER 0xF0
#define ISSI_INTERRUPTSTATUSREGISTER 0xF1
-#define ISSI_PAGE_LEDCONTROL 0x00 // PG0
-#define ISSI_PAGE_PWM 0x01 // PG1
-#define ISSI_PAGE_AUTOBREATH 0x02 // PG2
-#define ISSI_PAGE_FUNCTION 0x03 // PG3
-
-#define ISSI_REG_CONFIGURATION 0x00 // PG3
-#define ISSI_REG_GLOBALCURRENT 0x01 // PG3
-#define ISSI_REG_RESET 0x11 // PG3
-#define ISSI_REG_SWPULLUP 0x0F // PG3
-#define ISSI_REG_CSPULLUP 0x10 // PG3
+#define ISSI_PAGE_LEDCONTROL 0x00 // PG0
+#define ISSI_PAGE_PWM 0x01 // PG1
+#define ISSI_PAGE_AUTOBREATH 0x02 // PG2
+#define ISSI_PAGE_FUNCTION 0x03 // PG3
+
+#define ISSI_REG_CONFIGURATION 0x00 // PG3
+#define ISSI_REG_GLOBALCURRENT 0x01 // PG3
+#define ISSI_REG_RESET 0x11 // PG3
+#define ISSI_REG_SWPULLUP 0x0F // PG3
+#define ISSI_REG_CSPULLUP 0x10 // PG3
#ifndef ISSI_TIMEOUT
# define ISSI_TIMEOUT 100
diff --git a/drivers/led/issi/is31fl3736.h b/drivers/led/issi/is31fl3736.h
index 9fbe1cc577..f126034615 100644
--- a/drivers/led/issi/is31fl3736.h
+++ b/drivers/led/issi/is31fl3736.h
@@ -61,14 +61,14 @@ void IS31FL3736_mono_set_led_control_register(uint8_t index, bool enabled);
void IS31FL3736_update_pwm_buffers(uint8_t addr1, uint8_t addr2);
void IS31FL3736_update_led_control_registers(uint8_t addr1, uint8_t addr2);
-#define PUR_0R 0x00 // No PUR resistor
-#define PUR_05KR 0x01 // 0.5k Ohm resistor
-#define PUR_1KR 0x02 // 1.0k Ohm resistor
-#define PUR_2KR 0x03 // 2.0k Ohm resistor
-#define PUR_4KR 0x04 // 4.0k Ohm resistor
-#define PUR_8KR 0x05 // 8.0k Ohm resistor
-#define PUR_16KR 0x06 // 16k Ohm resistor
-#define PUR_32KR 0x07 // 32k Ohm resistor
+#define PUR_0R 0x00 // No PUR resistor
+#define PUR_05KR 0x01 // 0.5k Ohm resistor
+#define PUR_1KR 0x02 // 1.0k Ohm resistor
+#define PUR_2KR 0x03 // 2.0k Ohm resistor
+#define PUR_4KR 0x04 // 4.0k Ohm resistor
+#define PUR_8KR 0x05 // 8.0k Ohm resistor
+#define PUR_16KR 0x06 // 16k Ohm resistor
+#define PUR_32KR 0x07 // 32k Ohm resistor
#define A_1 0x00
#define A_2 0x02
diff --git a/drivers/led/issi/is31fl3737.c b/drivers/led/issi/is31fl3737.c
index 0722e18869..9f2a13de45 100644
--- a/drivers/led/issi/is31fl3737.c
+++ b/drivers/led/issi/is31fl3737.c
@@ -38,16 +38,16 @@
#define ISSI_INTERRUPTMASKREGISTER 0xF0
#define ISSI_INTERRUPTSTATUSREGISTER 0xF1
-#define ISSI_PAGE_LEDCONTROL 0x00 // PG0
-#define ISSI_PAGE_PWM 0x01 // PG1
-#define ISSI_PAGE_AUTOBREATH 0x02 // PG2
-#define ISSI_PAGE_FUNCTION 0x03 // PG3
-
-#define ISSI_REG_CONFIGURATION 0x00 // PG3
-#define ISSI_REG_GLOBALCURRENT 0x01 // PG3
-#define ISSI_REG_RESET 0x11 // PG3
-#define ISSI_REG_SWPULLUP 0x0F // PG3
-#define ISSI_REG_CSPULLUP 0x10 // PG3
+#define ISSI_PAGE_LEDCONTROL 0x00 // PG0
+#define ISSI_PAGE_PWM 0x01 // PG1
+#define ISSI_PAGE_AUTOBREATH 0x02 // PG2
+#define ISSI_PAGE_FUNCTION 0x03 // PG3
+
+#define ISSI_REG_CONFIGURATION 0x00 // PG3
+#define ISSI_REG_GLOBALCURRENT 0x01 // PG3
+#define ISSI_REG_RESET 0x11 // PG3
+#define ISSI_REG_SWPULLUP 0x0F // PG3
+#define ISSI_REG_CSPULLUP 0x10 // PG3
#ifndef ISSI_TIMEOUT
# define ISSI_TIMEOUT 100
diff --git a/drivers/led/issi/is31fl3737.h b/drivers/led/issi/is31fl3737.h
index 31b1a22267..ddb70a9df5 100644
--- a/drivers/led/issi/is31fl3737.h
+++ b/drivers/led/issi/is31fl3737.h
@@ -48,14 +48,14 @@ void IS31FL3737_set_led_control_register(uint8_t index, bool red, bool green, bo
void IS31FL3737_update_pwm_buffers(uint8_t addr1, uint8_t addr2);
void IS31FL3737_update_led_control_registers(uint8_t addr1, uint8_t addr2);
-#define PUR_0R 0x00 // No PUR resistor
-#define PUR_05KR 0x01 // 0.5k Ohm resistor in t_NOL
-#define PUR_1KR 0x02 // 1.0k Ohm resistor in t_NOL
-#define PUR_2KR 0x03 // 2.0k Ohm resistor in t_NOL
-#define PUR_4KR 0x04 // 4.0k Ohm resistor in t_NOL
-#define PUR_8KR 0x05 // 8.0k Ohm resistor in t_NOL
-#define PUR_16KR 0x06 // 16k Ohm resistor in t_NOL
-#define PUR_32KR 0x07 // 32k Ohm resistor in t_NOL
+#define PUR_0R 0x00 // No PUR resistor
+#define PUR_05KR 0x01 // 0.5k Ohm resistor in t_NOL
+#define PUR_1KR 0x02 // 1.0k Ohm resistor in t_NOL
+#define PUR_2KR 0x03 // 2.0k Ohm resistor in t_NOL
+#define PUR_4KR 0x04 // 4.0k Ohm resistor in t_NOL
+#define PUR_8KR 0x05 // 8.0k Ohm resistor in t_NOL
+#define PUR_16KR 0x06 // 16k Ohm resistor in t_NOL
+#define PUR_32KR 0x07 // 32k Ohm resistor in t_NOL
#define A_1 0x00
#define A_2 0x01
diff --git a/drivers/led/issi/is31fl3741.c b/drivers/led/issi/is31fl3741.c
index 8d347a5e60..393b0179b5 100644
--- a/drivers/led/issi/is31fl3741.c
+++ b/drivers/led/issi/is31fl3741.c
@@ -42,16 +42,16 @@
#define ISSI_INTERRUPTSTATUSREGISTER 0xF1
#define ISSI_IDREGISTER 0xFC
-#define ISSI_PAGE_PWM0 0x00 // PG0
-#define ISSI_PAGE_PWM1 0x01 // PG1
-#define ISSI_PAGE_SCALING_0 0x02 // PG2
-#define ISSI_PAGE_SCALING_1 0x03 // PG3
-#define ISSI_PAGE_FUNCTION 0x04 // PG4
-
-#define ISSI_REG_CONFIGURATION 0x00 // PG4
-#define ISSI_REG_GLOBALCURRENT 0x01 // PG4
-#define ISSI_REG_PULLDOWNUP 0x02 // PG4
-#define ISSI_REG_RESET 0x3F // PG4
+#define ISSI_PAGE_PWM0 0x00 // PG0
+#define ISSI_PAGE_PWM1 0x01 // PG1
+#define ISSI_PAGE_SCALING_0 0x02 // PG2
+#define ISSI_PAGE_SCALING_1 0x03 // PG3
+#define ISSI_PAGE_FUNCTION 0x04 // PG4
+
+#define ISSI_REG_CONFIGURATION 0x00 // PG4
+#define ISSI_REG_GLOBALCURRENT 0x01 // PG4
+#define ISSI_REG_PULLDOWNUP 0x02 // PG4
+#define ISSI_REG_RESET 0x3F // PG4
#ifndef ISSI_TIMEOUT
# define ISSI_TIMEOUT 100
diff --git a/drivers/led/issi/is31fl3741.h b/drivers/led/issi/is31fl3741.h
index 8154f8be70..3bdb23bd2d 100644
--- a/drivers/led/issi/is31fl3741.h
+++ b/drivers/led/issi/is31fl3741.h
@@ -51,14 +51,14 @@ void IS31FL3741_set_scaling_registers(const is31_led *pled, uint8_t red, uint8_t
void IS31FL3741_set_pwm_buffer(const is31_led *pled, uint8_t red, uint8_t green, uint8_t blue);
-#define PUR_0R 0x00 // No PUR resistor
-#define PUR_05KR 0x01 // 0.5k Ohm resistor
-#define PUR_1KR 0x02 // 1.0k Ohm resistor
-#define PUR_2KR 0x03 // 2.0k Ohm resistor
-#define PUR_4KR 0x04 // 4.0k Ohm resistor
-#define PUR_8KR 0x05 // 8.0k Ohm resistor
-#define PUR_16KR 0x06 // 16k Ohm resistor
-#define PUR_32KR 0x07 // 32k Ohm resistor
+#define PUR_0R 0x00 // No PUR resistor
+#define PUR_05KR 0x01 // 0.5k Ohm resistor
+#define PUR_1KR 0x02 // 1.0k Ohm resistor
+#define PUR_2KR 0x03 // 2.0k Ohm resistor
+#define PUR_4KR 0x04 // 4.0k Ohm resistor
+#define PUR_8KR 0x05 // 8.0k Ohm resistor
+#define PUR_16KR 0x06 // 16k Ohm resistor
+#define PUR_32KR 0x07 // 32k Ohm resistor
#define CS1_SW1 0x00
#define CS2_SW1 0x01
diff --git a/drivers/led/issi/is31fl3742.h b/drivers/led/issi/is31fl3742.h
new file mode 100644
index 0000000000..c96f12d0f1
--- /dev/null
+++ b/drivers/led/issi/is31fl3742.h
@@ -0,0 +1,299 @@
+/* Copyright 2017 Jason Williams
+ * Copyright 2018 Jack Humbert
+ * Copyright 2018 Yiancar
+ * Copyright 2020 MelGeek
+ * Copyright 2021 MasterSpoon
+ *
+ * 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 2 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/>.
+ */
+
+#pragma once
+
+// This is a 7-bit address, that gets left-shifted and bit 0
+// set to 0 for write, 1 for read (as per I2C protocol)
+// The address will vary depending on your wiring:
+// 00 <-> GND
+// 01 <-> SCL
+// 10 <-> SDA
+// 11 <-> VCC
+// ADDR represents A1:A0 of the 7-bit address.
+// The result is: 0b01100(ADDR)
+#ifndef DRIVER_ADDR_1
+# define DRIVER_ADDR_1 0b0110000
+#endif
+
+// Command Registers
+#define ISSI_COMMANDREGISTER_WRITELOCK 0xFE
+#define ISSI_COMMANDREGISTER 0xFD
+#define ISSI_IDREGISTER 0xFC
+#define ISSI_REGISTER_UNLOCK 0xC5
+
+// Response Registers
+#define ISSI_PAGE_PWM 0x00
+#define ISSI_PAGE_SCALING 0x02
+#define ISSI_PAGE_FUNCTION 0x04
+
+// Registers under Function Register
+#define ISSI_REG_CONFIGURATION 0x00
+#define ISSI_REG_GLOBALCURRENT 0x01
+#define ISSI_REG_PULLDOWNUP 0x02
+#define ISSI_REG_SSR 0x41
+#define ISSI_REG_RESET 0x3F
+#define ISSI_REG_PWM_SET 0x36
+
+// Set defaults for Function Registers
+#ifndef ISSI_CONFIGURATION
+# define ISSI_CONFIGURATION 0x31
+#endif
+#ifndef ISSI_GLOBALCURRENT
+# define ISSI_GLOBALCURRENT 0xFF
+#endif
+#ifndef ISSI_PULLDOWNUP
+# define ISSI_PULLDOWNUP 0x55
+#endif
+#ifndef ISSI_PWM_SET
+# define ISSI_PWM_SET 0x00
+#endif
+
+// Set defaults for Spread Spectrum Register
+#ifndef ISSI_SSR_1
+# define ISSI_SSR_1 0x00
+#endif
+#ifndef ISSI_SSR_2
+# define ISSI_SSR_2 0x00
+#endif
+#ifndef ISSI_SSR_3
+# define ISSI_SSR_3 0x00
+#endif
+#ifndef ISSI_SSR_4
+# define ISSI_SSR_4 0x00
+#endif
+
+// Set defaults for Scaling registers
+#ifndef ISSI_SCAL_RED
+# define ISSI_SCAL_RED 0xFF
+#endif
+#ifndef ISSI_SCAL_BLUE
+# define ISSI_SCAL_BLUE 0xFF
+#endif
+#ifndef ISSI_SCAL_GREEN
+# define ISSI_SCAL_GREEN 0xFF
+#endif
+#define ISSI_SCAL_RED_OFF 0x00
+#define ISSI_SCAL_GREEN_OFF 0x00
+#define ISSI_SCAL_BLUE_OFF 0x00
+
+#ifndef ISSI_SCAL_LED
+# define ISSI_SCAL_LED 0xFF
+#endif
+#define ISSI_SCAL_LED_OFF 0x00
+
+// Set buffer sizes
+#define ISSI_MAX_LEDS 180
+#define ISSI_SCALING_SIZE 180
+#define ISSI_PWM_TRF_SIZE 18
+#define ISSI_SCALING_TRF_SIZE 18
+
+// Location of 1st bit for PWM and Scaling registers
+#define ISSI_PWM_REG_1ST 0x00
+#define ISSI_SCL_REG_1ST 0x00
+
+// Map CS SW locations to order in PWM / Scaling buffers
+// This matches the ORDER in the Datasheet Register not the POSITION
+// It will always count from 0x00 to (ISSI_MAX_LEDS - 1)
+#define CS1_SW1 0x00
+#define CS2_SW1 0x01
+#define CS3_SW1 0x02
+#define CS4_SW1 0x03
+#define CS5_SW1 0x04
+#define CS6_SW1 0x05
+#define CS7_SW1 0x06
+#define CS8_SW1 0x07
+#define CS9_SW1 0x08
+#define CS10_SW1 0x09
+#define CS11_SW1 0x0A
+#define CS12_SW1 0x0B
+#define CS13_SW1 0x0C
+#define CS14_SW1 0x0D
+#define CS15_SW1 0x0E
+#define CS16_SW1 0x0F
+#define CS17_SW1 0x10
+#define CS18_SW1 0x11
+#define CS19_SW1 0x12
+#define CS20_SW1 0x13
+#define CS21_SW1 0x14
+#define CS22_SW1 0x15
+#define CS23_SW1 0x16
+#define CS24_SW1 0x17
+#define CS25_SW1 0x18
+#define CS26_SW1 0x19
+#define CS27_SW1 0x1A
+#define CS28_SW1 0x1B
+#define CS29_SW1 0x1C
+#define CS30_SW1 0x1D
+
+#define CS1_SW2 0x1E
+#define CS2_SW2 0x1F
+#define CS3_SW2 0x20
+#define CS4_SW2 0x21
+#define CS5_SW2 0x22
+#define CS6_SW2 0x23
+#define CS7_SW2 0x24
+#define CS8_SW2 0x25
+#define CS9_SW2 0x26
+#define CS10_SW2 0x27
+#define CS11_SW2 0x28
+#define CS12_SW2 0x29
+#define CS13_SW2 0x2A
+#define CS14_SW2 0x2B
+#define CS15_SW2 0x2C
+#define CS16_SW2 0x2D
+#define CS17_SW2 0x2E
+#define CS18_SW2 0x2F
+#define CS19_SW2 0x30
+#define CS20_SW2 0x31
+#define CS21_SW2 0x32
+#define CS22_SW2 0x33
+#define CS23_SW2 0x34
+#define CS24_SW2 0x35
+#define CS25_SW2 0x36
+#define CS26_SW2 0x37
+#define CS27_SW2 0x38
+#define CS28_SW2 0x39
+#define CS29_SW2 0x3A
+#define CS30_SW2 0x3B
+
+#define CS1_SW3 0x3C
+#define CS2_SW3 0x3D
+#define CS3_SW3 0x3E
+#define CS4_SW3 0x3F
+#define CS5_SW3 0x40
+#define CS6_SW3 0x41
+#define CS7_SW3 0x42
+#define CS8_SW3 0x43
+#define CS9_SW3 0x44
+#define CS10_SW3 0x45
+#define CS11_SW3 0x46
+#define CS12_SW3 0x47
+#define CS13_SW3 0x48
+#define CS14_SW3 0x49
+#define CS15_SW3 0x4A
+#define CS16_SW3 0x4B
+#define CS17_SW3 0x4C
+#define CS18_SW3 0x4D
+#define CS19_SW3 0x4E
+#define CS20_SW3 0x4F
+#define CS21_SW3 0x50
+#define CS22_SW3 0x51
+#define CS23_SW3 0x52
+#define CS24_SW3 0x53
+#define CS25_SW3 0x54
+#define CS26_SW3 0x55
+#define CS27_SW3 0x56
+#define CS28_SW3 0x57
+#define CS29_SW3 0x58
+#define CS30_SW3 0x59
+
+#define CS1_SW4 0x5A
+#define CS2_SW4 0x5B
+#define CS3_SW4 0x5C
+#define CS4_SW4 0x5D
+#define CS5_SW4 0x5E
+#define CS6_SW4 0x5F
+#define CS7_SW4 0x60
+#define CS8_SW4 0x61
+#define CS9_SW4 0x62
+#define CS10_SW4 0x63
+#define CS11_SW4 0x64
+#define CS12_SW4 0x65
+#define CS13_SW4 0x66
+#define CS14_SW4 0x67
+#define CS15_SW4 0x68
+#define CS16_SW4 0x69
+#define CS17_SW4 0x6A
+#define CS18_SW4 0x6B
+#define CS19_SW4 0x6C
+#define CS20_SW4 0x6D
+#define CS21_SW4 0x6E
+#define CS22_SW4 0x6F
+#define CS23_SW4 0x70
+#define CS24_SW4 0x71
+#define CS25_SW4 0x72
+#define CS26_SW4 0x73
+#define CS27_SW4 0x74
+#define CS28_SW4 0x75
+#define CS29_SW4 0x76
+#define CS30_SW4 0x77
+
+#define CS1_SW5 0x78
+#define CS2_SW5 0x79
+#define CS3_SW5 0x7A
+#define CS4_SW5 0x7B
+#define CS5_SW5 0x7C
+#define CS6_SW5 0x7D
+#define CS7_SW5 0x7E
+#define CS8_SW5 0x7F
+#define CS9_SW5 0x80
+#define CS10_SW5 0x81
+#define CS11_SW5 0x82
+#define CS12_SW5 0x83
+#define CS13_SW5 0x84
+#define CS14_SW5 0x85
+#define CS15_SW5 0x86
+#define CS16_SW5 0x87
+#define CS17_SW5 0x88
+#define CS18_SW5 0x89
+#define CS19_SW5 0x8A
+#define CS20_SW5 0x8B
+#define CS21_SW5 0x8C
+#define CS22_SW5 0x8D
+#define CS23_SW5 0x8E
+#define CS24_SW5 0x8F
+#define CS25_SW5 0x90
+#define CS26_SW5 0x91
+#define CS27_SW5 0x92
+#define CS28_SW5 0x93
+#define CS29_SW5 0x94
+#define CS30_SW5 0x95
+
+#define CS1_SW6 0x96
+#define CS2_SW6 0x97
+#define CS3_SW6 0x98
+#define CS4_SW6 0x99
+#define CS5_SW6 0x9A
+#define CS6_SW6 0x9B
+#define CS7_SW6 0x9C
+#define CS8_SW6 0x9D
+#define CS9_SW6 0x9E
+#define CS10_SW6 0x9F
+#define CS11_SW6 0xA0
+#define CS12_SW6 0xA1
+#define CS13_SW6 0xA2
+#define CS14_SW6 0xA3
+#define CS15_SW6 0xA4
+#define CS16_SW6 0xA5
+#define CS17_SW6 0xA6
+#define CS18_SW6 0xA7
+#define CS19_SW6 0xA8
+#define CS20_SW6 0xA9
+#define CS21_SW6 0xAA
+#define CS22_SW6 0xAB
+#define CS23_SW6 0xAC
+#define CS24_SW6 0xAD
+#define CS25_SW6 0xAE
+#define CS26_SW6 0xAF
+#define CS27_SW6 0xB0
+#define CS28_SW6 0xB1
+#define CS29_SW6 0xB2
+#define CS30_SW6 0xB3
diff --git a/drivers/led/issi/is31fl3743.h b/drivers/led/issi/is31fl3743.h
new file mode 100644
index 0000000000..d8fcd79096
--- /dev/null
+++ b/drivers/led/issi/is31fl3743.h
@@ -0,0 +1,327 @@
+/* Copyright 2017 Jason Williams
+ * Copyright 2018 Jack Humbert
+ * Copyright 2018 Yiancar
+ * Copyright 2020 MelGeek
+ * Copyright 2021 MasterSpoon
+ *
+ * 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 2 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/>.
+ */
+
+#pragma once
+
+// This is a 7-bit address, that gets left-shifted and bit 0
+// set to 0 for write, 1 for read (as per I2C protocol)
+// The address will vary depending on your wiring:
+// 00 <-> GND
+// 01 <-> SCL
+// 10 <-> SDA
+// 11 <-> VCC
+// ADDR1 represents A1:A0 of the 7-bit address.
+// ADDR2 represents A3:A2 of the 7-bit address.
+// The result is: 0b010(ADDR2)(ADDR1)
+#ifndef DRIVER_ADDR_1
+# define DRIVER_ADDR_1 0b0100000
+#endif
+
+// Set defaults for Spread Spectrum Register
+#ifndef ISSI_SSR_1
+# if DRIVER_COUNT == 1
+# define ISSI_SSR_1 0x00
+# else
+# define ISSI_SSR_1 0xC0
+# endif
+#endif
+#ifndef ISSI_SSR_2
+# define ISSI_SSR_2 0x80
+#endif
+#ifndef ISSI_SSR_3
+# define ISSI_SSR_3 0x80
+#endif
+#ifndef ISSI_SSR_4
+# define ISSI_SSR_4 0x80
+#endif
+
+// Command Registers
+#define ISSI_COMMANDREGISTER_WRITELOCK 0xFE
+#define ISSI_COMMANDREGISTER 0xFD
+#define ISSI_IDREGISTER 0xFC
+#define ISSI_REGISTER_UNLOCK 0xC5
+
+// Response Registers
+#define ISSI_PAGE_PWM 0x00
+#define ISSI_PAGE_SCALING 0x01
+#define ISSI_PAGE_FUNCTION 0x02
+
+// Registers under Function Register
+#define ISSI_REG_CONFIGURATION 0x00
+#define ISSI_REG_GLOBALCURRENT 0x01
+#define ISSI_REG_PULLDOWNUP 0x02
+#define ISSI_REG_TEMP 0x24
+#define ISSI_REG_SSR 0x25
+#define ISSI_REG_RESET 0x2F
+
+// Set defaults for Function Registers
+#ifndef ISSI_CONFIGURATION
+# define ISSI_CONFIGURATION 0x01
+#endif
+#ifndef ISSI_GLOBALCURRENT
+# define ISSI_GLOBALCURRENT 0xFF
+#endif
+#ifndef ISSI_PULLDOWNUP
+# define ISSI_PULLDOWNUP 0x33
+#endif
+#ifndef ISSI_TEMP
+# define ISSI_TEMP 0x00
+#endif
+
+// Set defaults for Scaling registers
+#ifndef ISSI_SCAL_RED
+# define ISSI_SCAL_RED 0xFF
+#endif
+#ifndef ISSI_SCAL_BLUE
+# define ISSI_SCAL_BLUE 0xFF
+#endif
+#ifndef ISSI_SCAL_GREEN
+# define ISSI_SCAL_GREEN 0xFF
+#endif
+#define ISSI_SCAL_RED_OFF 0x00
+#define ISSI_SCAL_GREEN_OFF 0x00
+#define ISSI_SCAL_BLUE_OFF 0x00
+
+#ifndef ISSI_SCAL_LED
+# define ISSI_SCAL_LED 0xFF
+#endif
+#define ISSI_SCAL_LED_OFF 0x00
+
+// Set buffer sizes
+#define ISSI_MAX_LEDS 198
+#define ISSI_SCALING_SIZE 198
+#define ISSI_PWM_TRF_SIZE 18
+#define ISSI_SCALING_TRF_SIZE 18
+
+// Location of 1st bit for PWM and Scaling registers
+#define ISSI_PWM_REG_1ST 0x01
+#define ISSI_SCL_REG_1ST 0x01
+
+// Map CS SW locations to order in PWM / Scaling buffers
+// This matches the ORDER in the Datasheet Register not the POSITION
+// It will always count from 0x00 to (ISSI_MAX_LEDS - 1)
+#define CS1_SW1 0x00
+#define CS2_SW1 0x01
+#define CS3_SW1 0x02
+#define CS4_SW1 0x03
+#define CS5_SW1 0x04
+#define CS6_SW1 0x05
+#define CS7_SW1 0x06
+#define CS8_SW1 0x07
+#define CS9_SW1 0x08
+#define CS10_SW1 0x09
+#define CS11_SW1 0x0A
+#define CS12_SW1 0x0B
+#define CS13_SW1 0x0C
+#define CS14_SW1 0x0D
+#define CS15_SW1 0x0E
+#define CS16_SW1 0x0F
+#define CS17_SW1 0x10
+#define CS18_SW1 0x11
+
+#define CS1_SW2 0x12
+#define CS2_SW2 0x13
+#define CS3_SW2 0x14
+#define CS4_SW2 0x15
+#define CS5_SW2 0x16
+#define CS6_SW2 0x17
+#define CS7_SW2 0x18
+#define CS8_SW2 0x19
+#define CS9_SW2 0x1A
+#define CS10_SW2 0x1B
+#define CS11_SW2 0x1C
+#define CS12_SW2 0x1D
+#define CS13_SW2 0x1E
+#define CS14_SW2 0x1F
+#define CS15_SW2 0x20
+#define CS16_SW2 0x21
+#define CS17_SW2 0x22
+#define CS18_SW2 0x23
+
+#define CS1_SW3 0x24
+#define CS2_SW3 0x25
+#define CS3_SW3 0x26
+#define CS4_SW3 0x27
+#define CS5_SW3 0x28
+#define CS6_SW3 0x29
+#define CS7_SW3 0x2A
+#define CS8_SW3 0x2B
+#define CS9_SW3 0x2C
+#define CS10_SW3 0x2D
+#define CS11_SW3 0x2E
+#define CS12_SW3 0x2F
+#define CS13_SW3 0x30
+#define CS14_SW3 0x31
+#define CS15_SW3 0x32
+#define CS16_SW3 0x33
+#define CS17_SW3 0x34
+#define CS18_SW3 0x35
+
+#define CS1_SW4 0x36
+#define CS2_SW4 0x37
+#define CS3_SW4 0x38
+#define CS4_SW4 0x39
+#define CS5_SW4 0x3A
+#define CS6_SW4 0x3B
+#define CS7_SW4 0x3C
+#define CS8_SW4 0x3D
+#define CS9_SW4 0x3E
+#define CS10_SW4 0x3F
+#define CS11_SW4 0x40
+#define CS12_SW4 0x41
+#define CS13_SW4 0x42
+#define CS14_SW4 0x43
+#define CS15_SW4 0x44
+#define CS16_SW4 0x45
+#define CS17_SW4 0x46
+#define CS18_SW4 0x47
+
+#define CS1_SW5 0x48
+#define CS2_SW5 0x49
+#define CS3_SW5 0x4A
+#define CS4_SW5 0x4B
+#define CS5_SW5 0x4C
+#define CS6_SW5 0x4D
+#define CS7_SW5 0x4E
+#define CS8_SW5 0x4F
+#define CS9_SW5 0x50
+#define CS10_SW5 0x51
+#define CS11_SW5 0x52
+#define CS12_SW5 0x53
+#define CS13_SW5 0x54
+#define CS14_SW5 0x55
+#define CS15_SW5 0x56
+#define CS16_SW5 0x57
+#define CS17_SW5 0x58
+#define CS18_SW5 0x59
+
+#define CS1_SW6 0x5A
+#define CS2_SW6 0x5B
+#define CS3_SW6 0x5C
+#define CS4_SW6 0x5D
+#define CS5_SW6 0x5E
+#define CS6_SW6 0x5F
+#define CS7_SW6 0x60
+#define CS8_SW6 0x61
+#define CS9_SW6 0x62
+#define CS10_SW6 0x63
+#define CS11_SW6 0x64
+#define CS12_SW6 0x65
+#define CS13_SW6 0x66
+#define CS14_SW6 0x67
+#define CS15_SW6 0x68
+#define CS16_SW6 0x69
+#define CS17_SW6 0x6A
+#define CS18_SW6 0x6B
+
+#define CS1_SW7 0x6C
+#define CS2_SW7 0x6D
+#define CS3_SW7 0x6E
+#define CS4_SW7 0x6F
+#define CS5_SW7 0x70
+#define CS6_SW7 0x71
+#define CS7_SW7 0x72
+#define CS8_SW7 0x73
+#define CS9_SW7 0x74
+#define CS10_SW7 0x75
+#define CS11_SW7 0x76
+#define CS12_SW7 0x77
+#define CS13_SW7 0x78
+#define CS14_SW7 0x79
+#define CS15_SW7 0x7A
+#define CS16_SW7 0x7B
+#define CS17_SW7 0x7C
+#define CS18_SW7 0x7D
+
+#define CS1_SW8 0x7E
+#define CS2_SW8 0x7F
+#define CS3_SW8 0x80
+#define CS4_SW8 0x81
+#define CS5_SW8 0x82
+#define CS6_SW8 0x83
+#define CS7_SW8 0x84
+#define CS8_SW8 0x85
+#define CS9_SW8 0x86
+#define CS10_SW8 0x87
+#define CS11_SW8 0x88
+#define CS12_SW8 0x89
+#define CS13_SW8 0x8A
+#define CS14_SW8 0x8B
+#define CS15_SW8 0x8C
+#define CS16_SW8 0x8D
+#define CS17_SW8 0x8E
+#define CS18_SW8 0x8F
+
+#define CS1_SW9 0x90
+#define CS2_SW9 0x91
+#define CS3_SW9 0x92
+#define CS4_SW9 0x93
+#define CS5_SW9 0x94
+#define CS6_SW9 0x95
+#define CS7_SW9 0x96
+#define CS8_SW9 0x97
+#define CS9_SW9 0x98
+#define CS10_SW9 0x99
+#define CS11_SW9 0x9A
+#define CS12_SW9 0x9B
+#define CS13_SW9 0x9C
+#define CS14_SW9 0x9D
+#define CS15_SW9 0x9E
+#define CS16_SW9 0x9F
+#define CS17_SW9 0xA0
+#define CS18_SW9 0xA1
+
+#define CS1_SW10 0xA2
+#define CS2_SW10 0xA3
+#define CS3_SW10 0xA4
+#define CS4_SW10 0xA5
+#define CS5_SW10 0xA6
+#define CS6_SW10 0xA7
+#define CS7_SW10 0xA8
+#define CS8_SW10 0xA9
+#define CS9_SW10 0xAA
+#define CS10_SW10 0xAB
+#define CS11_SW10 0xAC
+#define CS12_SW10 0xAD
+#define CS13_SW10 0xAE
+#define CS14_SW10 0xAF
+#define CS15_SW10 0xB0
+#define CS16_SW10 0xB1
+#define CS17_SW10 0xB2
+#define CS18_SW10 0xB3
+
+#define CS1_SW11 0xB4
+#define CS2_SW11 0xB5
+#define CS3_SW11 0xB6
+#define CS4_SW11 0xB7
+#define CS5_SW11 0xB8
+#define CS6_SW11 0xB9
+#define CS7_SW11 0xBA
+#define CS8_SW11 0xBB
+#define CS9_SW11 0xBC
+#define CS10_SW11 0xBD
+#define CS11_SW11 0xBE
+#define CS12_SW11 0xBF
+#define CS13_SW11 0xC0
+#define CS14_SW11 0xC1
+#define CS15_SW11 0xC2
+#define CS16_SW11 0xC3
+#define CS17_SW11 0xC4
+#define CS18_SW11 0xC5
diff --git a/drivers/led/issi/is31fl3745.h b/drivers/led/issi/is31fl3745.h
new file mode 100644
index 0000000000..ca5dd4a986
--- /dev/null
+++ b/drivers/led/issi/is31fl3745.h
@@ -0,0 +1,270 @@
+/* Copyright 2017 Jason Williams
+ * Copyright 2018 Jack Humbert
+ * Copyright 2018 Yiancar
+ * Copyright 2020 MelGeek
+ * Copyright 2021 MasterSpoon
+ *
+ * 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 2 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/>.
+ */
+
+#pragma once
+
+// This is a 7-bit address, that gets left-shifted and bit 0
+// set to 0 for write, 1 for read (as per I2C protocol)
+// The address will vary depending on your wiring:
+// 00 <-> GND
+// 01 <-> SCL
+// 10 <-> SDA
+// 11 <-> VCC
+// ADDR1 represents A1:A0 of the 7-bit address.
+// ADDR2 represents A3:A2 of the 7-bit address.
+// The result is: 0b010(ADDR2)(ADDR1)
+#ifndef DRIVER_ADDR_1
+# define DRIVER_ADDR_1 0b0100000
+#endif
+
+// Set defaults for Spread Spectrum Register
+#ifndef ISSI_SSR_1
+# if DRIVER_COUNT == 1
+# define ISSI_SSR_1 0x00
+# else
+# define ISSI_SSR_1 0xC0
+# endif
+#endif
+#ifndef ISSI_SSR_2
+# define ISSI_SSR_2 0x80
+#endif
+#ifndef ISSI_SSR_3
+# define ISSI_SSR_3 0x80
+#endif
+#ifndef ISSI_SSR_4
+# define ISSI_SSR_4 0x80
+#endif
+
+// Command Registers
+#define ISSI_COMMANDREGISTER_WRITELOCK 0xFE
+#define ISSI_COMMANDREGISTER 0xFD
+#define ISSI_IDREGISTER 0xFC
+#define ISSI_REGISTER_UNLOCK 0xC5
+
+// Response Registers
+#define ISSI_PAGE_PWM 0x00
+#define ISSI_PAGE_SCALING 0x01
+#define ISSI_PAGE_FUNCTION 0x02
+
+// Registers under Function Register
+#define ISSI_REG_CONFIGURATION 0x00
+#define ISSI_REG_GLOBALCURRENT 0x01
+#define ISSI_REG_PULLDOWNUP 0x02
+#define ISSI_REG_TEMP 0x24
+#define ISSI_REG_SSR 0x25
+#define ISSI_REG_RESET 0x2F
+
+// Set defaults for Function Registers
+#ifndef ISSI_CONFIGURATION
+# define ISSI_CONFIGURATION 0x31
+#endif
+#ifndef ISSI_GLOBALCURRENT
+# define ISSI_GLOBALCURRENT 0xFF
+#endif
+#ifndef ISSI_PULLDOWNUP
+# define ISSI_PULLDOWNUP 0x33
+#endif
+#ifndef ISSI_TEMP
+# define ISSI_TEMP 0x00
+#endif
+
+// Set defaults for Scaling registers
+#ifndef ISSI_SCAL_RED
+# define ISSI_SCAL_RED 0xFF
+#endif
+#ifndef ISSI_SCAL_BLUE
+# define ISSI_SCAL_BLUE 0xFF
+#endif
+#ifndef ISSI_SCAL_GREEN
+# define ISSI_SCAL_GREEN 0xFF
+#endif
+#define ISSI_SCAL_RED_OFF 0x00
+#define ISSI_SCAL_GREEN_OFF 0x00
+#define ISSI_SCAL_BLUE_OFF 0x00
+
+#ifndef ISSI_SCAL_LED
+# define ISSI_SCAL_LED 0xFF
+#endif
+#define ISSI_SCAL_LED_OFF 0x00
+
+// Set buffer sizes
+#define ISSI_MAX_LEDS 144
+#define ISSI_SCALING_SIZE 144
+#define ISSI_PWM_TRF_SIZE 18
+#define ISSI_SCALING_TRF_SIZE 18
+
+// Location of 1st bit for PWM and Scaling registers
+#define ISSI_PWM_REG_1ST 0x01
+#define ISSI_SCL_REG_1ST 0x01
+
+// Map CS SW locations to order in PWM / Scaling buffers
+// This matches the ORDER in the Datasheet Register not the POSITION
+// It will always count from 0x00 to (ISSI_MAX_LEDS - 1)
+#define CS1_SW1 0x00
+#define CS2_SW1 0x01
+#define CS3_SW1 0x02
+#define CS4_SW1 0x03
+#define CS5_SW1 0x04
+#define CS6_SW1 0x05
+#define CS7_SW1 0x06
+#define CS8_SW1 0x07
+#define CS9_SW1 0x08
+#define CS10_SW1 0x09
+#define CS11_SW1 0x0A
+#define CS12_SW1 0x0B
+#define CS13_SW1 0x0C
+#define CS14_SW1 0x0D
+#define CS15_SW1 0x0E
+#define CS16_SW1 0x0F
+#define CS17_SW1 0x10
+#define CS18_SW1 0x11
+
+#define CS1_SW2 0x12
+#define CS2_SW2 0x13
+#define CS3_SW2 0x14
+#define CS4_SW2 0x15
+#define CS5_SW2 0x16
+#define CS6_SW2 0x17
+#define CS7_SW2 0x18
+#define CS8_SW2 0x19
+#define CS9_SW2 0x1A
+#define CS10_SW2 0x1B
+#define CS11_SW2 0x1C
+#define CS12_SW2 0x1D
+#define CS13_SW2 0x1E
+#define CS14_SW2 0x1F
+#define CS15_SW2 0x20
+#define CS16_SW2 0x21
+#define CS17_SW2 0x22
+#define CS18_SW2 0x23
+
+#define CS1_SW3 0x24
+#define CS2_SW3 0x25
+#define CS3_SW3 0x26
+#define CS4_SW3 0x27
+#define CS5_SW3 0x28
+#define CS6_SW3 0x29
+#define CS7_SW3 0x2A
+#define CS8_SW3 0x2B
+#define CS9_SW3 0x2C
+#define CS10_SW3 0x2D
+#define CS11_SW3 0x2E
+#define CS12_SW3 0x2F
+#define CS13_SW3 0x30
+#define CS14_SW3 0x31
+#define CS15_SW3 0x32
+#define CS16_SW3 0x33
+#define CS17_SW3 0x34
+#define CS18_SW3 0x35
+
+#define CS1_SW4 0x36
+#define CS2_SW4 0x37
+#define CS3_SW4 0x38
+#define CS4_SW4 0x39
+#define CS5_SW4 0x3A
+#define CS6_SW4 0x3B
+#define CS7_SW4 0x3C
+#define CS8_SW4 0x3D
+#define CS9_SW4 0x3E
+#define CS10_SW4 0x3F
+#define CS11_SW4 0x40
+#define CS12_SW4 0x41
+#define CS13_SW4 0x42
+#define CS14_SW4 0x43
+#define CS15_SW4 0x44
+#define CS16_SW4 0x45
+#define CS17_SW4 0x46
+#define CS18_SW4 0x47
+
+#define CS1_SW5 0x48
+#define CS2_SW5 0x49
+#define CS3_SW5 0x4A
+#define CS4_SW5 0x4B
+#define CS5_SW5 0x4C
+#define CS6_SW5 0x4D
+#define CS7_SW5 0x4E
+#define CS8_SW5 0x4F
+#define CS9_SW5 0x50
+#define CS10_SW5 0x51
+#define CS11_SW5 0x52
+#define CS12_SW5 0x53
+#define CS13_SW5 0x54
+#define CS14_SW5 0x55
+#define CS15_SW5 0x56
+#define CS16_SW5 0x57
+#define CS17_SW5 0x58
+#define CS18_SW5 0x59
+
+#define CS1_SW6 0x5A
+#define CS2_SW6 0x5B
+#define CS3_SW6 0x5C
+#define CS4_SW6 0x5D
+#define CS5_SW6 0x5E
+#define CS6_SW6 0x5F
+#define CS7_SW6 0x60
+#define CS8_SW6 0x61
+#define CS9_SW6 0x62
+#define CS10_SW6 0x63
+#define CS11_SW6 0x64
+#define CS12_SW6 0x65
+#define CS13_SW6 0x66
+#define CS14_SW6 0x67
+#define CS15_SW6 0x68
+#define CS16_SW6 0x69
+#define CS17_SW6 0x6A
+#define CS18_SW6 0x6B
+
+#define CS1_SW7 0x6C
+#define CS2_SW7 0x6D
+#define CS3_SW7 0x6E
+#define CS4_SW7 0x6F
+#define CS5_SW7 0x70
+#define CS6_SW7 0x71
+#define CS7_SW7 0x72
+#define CS8_SW7 0x73
+#define CS9_SW7 0x74
+#define CS10_SW7 0x75
+#define CS11_SW7 0x76
+#define CS12_SW7 0x77
+#define CS13_SW7 0x78
+#define CS14_SW7 0x79
+#define CS15_SW7 0x7A
+#define CS16_SW7 0x7B
+#define CS17_SW7 0x7C
+#define CS18_SW7 0x7D
+
+#define CS1_SW8 0x7E
+#define CS2_SW8 0x7F
+#define CS3_SW8 0x80
+#define CS4_SW8 0x81
+#define CS5_SW8 0x82
+#define CS6_SW8 0x83
+#define CS7_SW8 0x84
+#define CS8_SW8 0x85
+#define CS9_SW8 0x86
+#define CS10_SW8 0x87
+#define CS11_SW8 0x88
+#define CS12_SW8 0x89
+#define CS13_SW8 0x8A
+#define CS14_SW8 0x8B
+#define CS15_SW8 0x8C
+#define CS16_SW8 0x8D
+#define CS17_SW8 0x8E
+#define CS18_SW8 0x8F
diff --git a/drivers/led/issi/is31fl3746.h b/drivers/led/issi/is31fl3746.h
new file mode 100644
index 0000000000..f89f281533
--- /dev/null
+++ b/drivers/led/issi/is31fl3746.h
@@ -0,0 +1,198 @@
+/* Copyright 2017 Jason Williams
+ * Copyright 2018 Jack Humbert
+ * Copyright 2018 Yiancar
+ * Copyright 2020 MelGeek
+ * Copyright 2021 MasterSpoon
+ *
+ * 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 2 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/>.
+ */
+
+#pragma once
+
+// This is a 7-bit address, that gets left-shifted and bit 0
+// set to 0 for write, 1 for read (as per I2C protocol)
+// The address will vary depending on your wiring:
+// 00 <-> GND
+// 01 <-> SCL
+// 10 <-> SDA
+// 11 <-> VCC
+// ADDR1 represents A1:A0 of the 7-bit address.
+// ADDR2 represents A3:A2 of the 7-bit address.
+// The result is: 0b110(ADDR2)(ADDR1)
+#ifndef DRIVER_ADDR_1
+# define DRIVER_ADDR_1 0b1100000
+#endif
+
+// Set defaults for Spread Spectrum Register
+#ifndef ISSI_SSR_1
+# define ISSI_SSR_1 0x00
+#endif
+#ifndef ISSI_SSR_2
+# define ISSI_SSR_2 0x00
+#endif
+#ifndef ISSI_SSR_3
+# define ISSI_SSR_3 0x00
+#endif
+#ifndef ISSI_SSR_4
+# define ISSI_SSR_4 0x00
+#endif
+
+// Command Registers
+#define ISSI_COMMANDREGISTER_WRITELOCK 0xFE
+#define ISSI_COMMANDREGISTER 0xFD
+#define ISSI_IDREGISTER 0xFC
+#define ISSI_REGISTER_UNLOCK 0xC5
+
+// Response Registers
+#define ISSI_PAGE_PWM 0x00
+#define ISSI_PAGE_SCALING 0x01
+#define ISSI_PAGE_FUNCTION 0x01
+
+// Registers under Function Register
+#define ISSI_REG_CONFIGURATION 0x50
+#define ISSI_REG_GLOBALCURRENT 0x51
+#define ISSI_REG_PULLDOWNUP 0x52
+#define ISSI_REG_TEMP 0x5F
+#define ISSI_REG_SSR 0x60
+#define ISSI_REG_RESET 0x8F
+#define ISSI_REG_PWM_ENABLE 0xE0
+#define ISSI_REG_PWM_SET 0xE2
+
+// Set defaults for Function Registers
+#ifndef ISSI_CONFIGURATION
+# define ISSI_CONFIGURATION 0x01
+#endif
+#ifndef ISSI_GLOBALCURRENT
+# define ISSI_GLOBALCURRENT 0xFF
+#endif
+#ifndef ISSI_PULLDOWNUP
+# define ISSI_PULLDOWNUP 0x33
+#endif
+#ifndef ISSI_TEMP
+# define ISSI_TEMP 0x00
+#endif
+#ifndef ISSI_PWM_ENABLE
+# define ISSI_PWM_ENABLE 0x00
+#endif
+#ifndef ISSI_PWM_SET
+# define ISSI_PWM_SET 0x00
+#endif
+
+// Set defaults for Scaling registers
+#ifndef ISSI_SCAL_RED
+# define ISSI_SCAL_RED 0xFF
+#endif
+#ifndef ISSI_SCAL_BLUE
+# define ISSI_SCAL_BLUE 0xFF
+#endif
+#ifndef ISSI_SCAL_GREEN
+# define ISSI_SCAL_GREEN 0xFF
+#endif
+#define ISSI_SCAL_RED_OFF 0x00
+#define ISSI_SCAL_GREEN_OFF 0x00
+#define ISSI_SCAL_BLUE_OFF 0x00
+
+#ifndef ISSI_SCAL_LED
+# define ISSI_SCAL_LED 0xFF
+#endif
+#define ISSI_SCAL_LED_OFF 0x00
+
+// Set buffer sizes
+#define ISSI_MAX_LEDS 72
+#define ISSI_SCALING_SIZE 72
+#define ISSI_PWM_TRF_SIZE 18
+#define ISSI_SCALING_TRF_SIZE 18
+
+// Location of 1st bit for PWM and Scaling registers
+#define ISSI_PWM_REG_1ST 0x01
+#define ISSI_SCL_REG_1ST 0x01
+
+// Map CS SW locations to order in PWM / Scaling buffers
+// This matches the ORDER in the Datasheet Register not the POSITION
+// It will always count from 0x00 to (ISSI_MAX_LEDS - 1)
+#define CS1_SW1 0x00
+#define CS2_SW1 0x01
+#define CS3_SW1 0x02
+#define CS4_SW1 0x03
+#define CS5_SW1 0x04
+#define CS6_SW1 0x05
+#define CS7_SW1 0x06
+#define CS8_SW1 0x07
+#define CS9_SW1 0x08
+#define CS10_SW1 0x09
+#define CS11_SW1 0x0A
+#define CS12_SW1 0x0B
+#define CS13_SW1 0x0C
+#define CS14_SW1 0x0D
+#define CS15_SW1 0x0E
+#define CS16_SW1 0x0F
+#define CS17_SW1 0x10
+#define CS18_SW1 0x11
+
+#define CS1_SW2 0x12
+#define CS2_SW2 0x13
+#define CS3_SW2 0x14
+#define CS4_SW2 0x15
+#define CS5_SW2 0x16
+#define CS6_SW2 0x17
+#define CS7_SW2 0x18
+#define CS8_SW2 0x19
+#define CS9_SW2 0x1A
+#define CS10_SW2 0x1B
+#define CS11_SW2 0x1C
+#define CS12_SW2 0x1D
+#define CS13_SW2 0x1E
+#define CS14_SW2 0x1F
+#define CS15_SW2 0x20
+#define CS16_SW2 0x21
+#define CS17_SW2 0x22
+#define CS18_SW2 0x23
+
+#define CS1_SW3 0x24
+#define CS2_SW3 0x25
+#define CS3_SW3 0x26
+#define CS4_SW3 0x27
+#define CS5_SW3 0x28
+#define CS6_SW3 0x29
+#define CS7_SW3 0x2A
+#define CS8_SW3 0x2B
+#define CS9_SW3 0x2C
+#define CS10_SW3 0x2D
+#define CS11_SW3 0x2E
+#define CS12_SW3 0x2F
+#define CS13_SW3 0x30
+#define CS14_SW3 0x31
+#define CS15_SW3 0x32
+#define CS16_SW3 0x33
+#define CS17_SW3 0x34
+#define CS18_SW3 0x35
+
+#define CS1_SW4 0x36
+#define CS2_SW4 0x37
+#define CS3_SW4 0x38
+#define CS4_SW4 0x39
+#define CS5_SW4 0x3A
+#define CS6_SW4 0x3B
+#define CS7_SW4 0x3C
+#define CS8_SW4 0x3D
+#define CS9_SW4 0x3E
+#define CS10_SW4 0x3F
+#define CS11_SW4 0x40
+#define CS12_SW4 0x41
+#define CS13_SW4 0x42
+#define CS14_SW4 0x43
+#define CS15_SW4 0x44
+#define CS16_SW4 0x45
+#define CS17_SW4 0x46
+#define CS18_SW4 0x47
diff --git a/drivers/led/issi/is31flcommon.c b/drivers/led/issi/is31flcommon.c
new file mode 100644
index 0000000000..9f4b2123ff
--- /dev/null
+++ b/drivers/led/issi/is31flcommon.c
@@ -0,0 +1,230 @@
+/* Copyright 2017 Jason Williams
+ * Copyright 2018 Jack Humbert
+ * Copyright 2018 Yiancar
+ * Copyright 2020 MelGeek
+ * Copyright 2021 MasterSpoon
+ *
+ * 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 2 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 "is31flcommon.h"
+#include "i2c_master.h"
+#include "wait.h"
+#include <string.h>
+
+// Set defaults for Timeout and Persistence
+#ifndef ISSI_TIMEOUT
+# define ISSI_TIMEOUT 100
+#endif
+#ifndef ISSI_PERSISTENCE
+# define ISSI_PERSISTENCE 0
+#endif
+
+// Transfer buffer for TWITransmitData()
+uint8_t g_twi_transfer_buffer[20];
+
+// These buffers match the PWM & scaling registers.
+// Storing them like this is optimal for I2C transfers to the registers.
+uint8_t g_pwm_buffer[DRIVER_COUNT][ISSI_MAX_LEDS];
+bool g_pwm_buffer_update_required[DRIVER_COUNT] = {false};
+
+uint8_t g_scaling_buffer[DRIVER_COUNT][ISSI_SCALING_SIZE];
+bool g_scaling_buffer_update_required[DRIVER_COUNT] = {false};
+
+// For writing of single register entry
+void IS31FL_write_single_register(uint8_t addr, uint8_t reg, uint8_t data) {
+ // Set register address and register data ready to write
+ g_twi_transfer_buffer[0] = reg;
+ g_twi_transfer_buffer[1] = data;
+
+#if ISSI_PERSISTENCE > 0
+ for (uint8_t i = 0; i < ISSI_PERSISTENCE; i++) {
+ if (i2c_transmit(addr << 1, g_twi_transfer_buffer, 2, ISSI_TIMEOUT) == 0) break;
+ }
+#else
+ i2c_transmit(addr << 1, g_twi_transfer_buffer, 2, ISSI_TIMEOUT);
+#endif
+}
+
+// For writing of mulitple register entries to make use of address auto increment
+// Once the controller has been called and we have written the first bit of data
+// the controller will move to the next register meaning we can write sequential blocks.
+bool IS31FL_write_multi_registers(uint8_t addr, uint8_t *source_buffer, uint8_t buffer_size, uint8_t transfer_size, uint8_t start_reg_addr) {
+ // Split the buffer into chunks to transfer
+ for (int i = 0; i < buffer_size; i += transfer_size) {
+ // Set the first entry of transfer buffer to the first register we want to write
+ g_twi_transfer_buffer[0] = i + start_reg_addr;
+ // Copy the section of our source buffer into the transfer buffer after first register address
+ memcpy(g_twi_transfer_buffer + 1, source_buffer + i, transfer_size);
+
+#if ISSI_PERSISTENCE > 0
+ for (uint8_t i = 0; i < ISSI_PERSISTENCE; i++) {
+ if (i2c_transmit(addr << 1, g_twi_transfer_buffer, transfer_size + 1, ISSI_TIMEOUT) != 0) {
+ return false;
+ }
+ }
+#else
+ if (i2c_transmit(addr << 1, g_twi_transfer_buffer, transfer_size + 1, ISSI_TIMEOUT) != 0) {
+ return false;
+ }
+#endif
+ }
+ return true;
+}
+
+void IS31FL_unlock_register(uint8_t addr, uint8_t page) {
+ // unlock the command register and select Page to write
+ IS31FL_write_single_register(addr, ISSI_COMMANDREGISTER_WRITELOCK, ISSI_REGISTER_UNLOCK);
+ IS31FL_write_single_register(addr, ISSI_COMMANDREGISTER, page);
+}
+
+void IS31FL_common_init(uint8_t addr, uint8_t ssr) {
+ // Setup phase, need to take out of software shutdown and configure
+ // ISSI_SSR_x is passed to allow Master / Slave setting where applicable
+
+ // Unlock the command register & select Function Register
+ IS31FL_unlock_register(addr, ISSI_PAGE_FUNCTION);
+ // Set Configuration Register to remove Software shutdown
+ IS31FL_write_single_register(addr, ISSI_REG_CONFIGURATION, ISSI_CONFIGURATION);
+ // Set Golbal Current Control Register
+ IS31FL_write_single_register(addr, ISSI_REG_GLOBALCURRENT, ISSI_GLOBALCURRENT);
+ // Set Pull up & Down for SWx CSy
+ IS31FL_write_single_register(addr, ISSI_REG_PULLDOWNUP, ISSI_PULLDOWNUP);
+// Set Tempature Status
+#ifdef ISSI_REG_TEMP
+ IS31FL_write_single_register(addr, ISSI_REG_TEMP, ISSI_TEMP);
+#endif
+ // Set Spread Spectrum Register, passed through as sets SYNC function
+ IS31FL_write_single_register(addr, ISSI_REG_SSR, ssr);
+// Set PWM Frequency Enable Register if applicable
+#ifdef ISSI_REG_PWM_ENABLE
+ IS31FL_write_single_register(addr, ISSI_REG_PWM_ENABLE, ISSI_PWM_ENABLE);
+#endif
+// Set PWM Frequency Register if applicable
+#ifdef ISSI_REG_PWM_SET
+ IS31FL_write_single_register(addr, ISSI_REG_PWM_SET, ISSI_PWM_SET);
+#endif
+
+ // Wait 10ms to ensure the device has woken up.
+ wait_ms(10);
+}
+
+void IS31FL_common_update_pwm_register(uint8_t addr, uint8_t index) {
+ if (g_pwm_buffer_update_required[index]) {
+ // Queue up the correct page
+ IS31FL_unlock_register(addr, ISSI_PAGE_PWM);
+ // Hand off the update to IS31FL_write_multi_registers
+ IS31FL_write_multi_registers(addr, g_pwm_buffer[index], ISSI_MAX_LEDS, ISSI_PWM_TRF_SIZE, ISSI_PWM_REG_1ST);
+ // Update flags that pwm_buffer has been updated
+ g_pwm_buffer_update_required[index] = false;
+ }
+}
+
+#ifdef ISSI_MANUAL_SCALING
+void IS31FL_set_manual_scaling_buffer(void) {
+ for (int i = 0; i < ISSI_MANUAL_SCALING; i++) {
+ is31_led scale = g_is31_scaling[i];
+ if (scale.driver >= 0 && scale.driver < DRIVER_LED_TOTAL) {
+ is31_led led = g_is31_leds[scale.driver];
+
+# ifdef RGB_MATRIX_ENABLE
+ g_scaling_buffer[led.driver][led.r] = scale.r;
+ g_scaling_buffer[led.driver][led.g] = scale.g;
+ g_scaling_buffer[led.driver][led.b] = scale.b;
+# elif defined(LED_MATRIX_ENABLE)
+ g_scaling_buffer[led.driver][led.v] = scale.v;
+# endif
+ g_scaling_buffer_update_required[led.driver] = true;
+ }
+ }
+}
+#endif
+
+void IS31FL_common_update_scaling_register(uint8_t addr, uint8_t index) {
+ if (g_scaling_buffer_update_required[index]) {
+ // Queue up the correct page
+ IS31FL_unlock_register(addr, ISSI_PAGE_SCALING);
+ // Hand off the update to IS31FL_write_multi_registers
+ IS31FL_write_multi_registers(addr, g_scaling_buffer[index], ISSI_SCALING_SIZE, ISSI_SCALING_TRF_SIZE, ISSI_SCL_REG_1ST);
+ // Update flags that scaling_buffer has been updated
+ g_scaling_buffer_update_required[index] = false;
+ }
+}
+
+#ifdef RGB_MATRIX_ENABLE
+// Colour is set by adjusting PWM register
+void IS31FL_RGB_set_color(int index, uint8_t red, uint8_t green, uint8_t blue) {
+ if (index >= 0 && index < DRIVER_LED_TOTAL) {
+ is31_led led = g_is31_leds[index];
+
+ g_pwm_buffer[led.driver][led.r] = red;
+ g_pwm_buffer[led.driver][led.g] = green;
+ g_pwm_buffer[led.driver][led.b] = blue;
+ g_pwm_buffer_update_required[led.driver] = true;
+ }
+}
+
+void IS31FL_RGB_set_color_all(uint8_t red, uint8_t green, uint8_t blue) {
+ for (int i = 0; i < DRIVER_LED_TOTAL; i++) {
+ IS31FL_RGB_set_color(i, red, green, blue);
+ }
+}
+
+// Setup Scaling register that decides the peak current of each LED
+void IS31FL_RGB_set_scaling_buffer(uint8_t index, bool red, bool green, bool blue) {
+ is31_led led = g_is31_leds[index];
+ if (red) {
+ g_scaling_buffer[led.driver][led.r] = ISSI_SCAL_RED;
+ } else {
+ g_scaling_buffer[led.driver][led.r] = ISSI_SCAL_RED_OFF;
+ }
+ if (green) {
+ g_scaling_buffer[led.driver][led.g] = ISSI_SCAL_GREEN;
+ } else {
+ g_scaling_buffer[led.driver][led.g] = ISSI_SCAL_GREEN_OFF;
+ }
+ if (blue) {
+ g_scaling_buffer[led.driver][led.b] = ISSI_SCAL_BLUE;
+ } else {
+ g_scaling_buffer[led.driver][led.b] = ISSI_SCAL_BLUE_OFF;
+ }
+ g_scaling_buffer_update_required[led.driver] = true;
+}
+
+#elif defined(LED_MATRIX_ENABLE)
+// LED Matrix Specific scripts
+void IS31FL_simple_set_scaling_buffer(uint8_t index, bool value) {
+ is31_led led = g_is31_leds[index];
+ if (value) {
+ g_scaling_buffer[led.driver][led.v] = ISSI_SCAL_LED;
+ } else {
+ g_scaling_buffer[led.driver][led.v] = ISSI_SCAL_LED_OFF;
+ }
+ g_scaling_buffer_update_required[led.driver] = true;
+}
+
+void IS31FL_simple_set_brightness(int index, uint8_t value) {
+ if (index >= 0 && index < DRIVER_LED_TOTAL) {
+ is31_led led = g_is31_leds[index];
+ g_pwm_buffer[led.driver][led.v] = value;
+ g_pwm_buffer_update_required[led.driver] = true;
+ }
+}
+
+void IS31FL_simple_set_brigntness_all(uint8_t value) {
+ for (int i = 0; i < DRIVER_LED_TOTAL; i++) {
+ IS31FL_simple_set_brightness(i, value);
+ }
+}
+#endif
diff --git a/drivers/led/issi/is31flcommon.h b/drivers/led/issi/is31flcommon.h
new file mode 100644
index 0000000000..77e9665e32
--- /dev/null
+++ b/drivers/led/issi/is31flcommon.h
@@ -0,0 +1,78 @@
+/* Copyright 2017 Jason Williams
+ * Copyright 2018 Jack Humbert
+ * Copyright 2018 Yiancar
+ * Copyright 2020 MelGeek
+ * Copyright 2021 MasterSpoon
+ *
+ * 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 2 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/>.
+ */
+
+#pragma once
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "progmem.h"
+
+// Which variant header file to use
+#ifdef IS31FL3742A
+# include "is31fl3742.h"
+#elif defined(IS31FL3743A)
+# include "is31fl3743.h"
+#elif defined(IS31FL3745)
+# include "is31fl3745.h"
+#elif defined(IS31FL3746A)
+# include "is31fl3746.h"
+#endif
+
+#ifdef RGB_MATRIX_ENABLE
+typedef struct is31_led {
+ uint8_t driver;
+ uint8_t r;
+ uint8_t g;
+ uint8_t b;
+} __attribute__((packed)) is31_led;
+
+#elif defined(LED_MATRIX_ENABLE)
+typedef struct is31_led {
+ uint8_t driver;
+ uint8_t v;
+} __attribute__((packed)) is31_led;
+#endif
+
+#ifdef ISSI_MANUAL_SCALING
+extern const is31_led __flash g_is31_scaling[];
+void IS31FL_set_manual_scaling_buffer(void);
+#endif
+
+extern const is31_led __flash g_is31_leds[DRIVER_LED_TOTAL];
+
+void IS31FL_write_single_register(uint8_t addr, uint8_t reg, uint8_t data);
+bool IS31FL_write_multi_registers(uint8_t addr, uint8_t *source_buffer, uint8_t buffer_size, uint8_t transfer_size, uint8_t start_reg_addr);
+void IS31FL_unlock_register(uint8_t addr, uint8_t page);
+void IS31FL_common_init(uint8_t addr, uint8_t ssr);
+
+void IS31FL_common_update_pwm_register(uint8_t addr, uint8_t index);
+void IS31FL_common_update_scaling_register(uint8_t addr, uint8_t index);
+
+#ifdef RGB_MATRIX_ENABLE
+// RGB Matrix Specific scripts
+void IS31FL_RGB_set_color(int index, uint8_t red, uint8_t green, uint8_t blue);
+void IS31FL_RGB_set_color_all(uint8_t red, uint8_t green, uint8_t blue);
+void IS31FL_RGB_set_scaling_buffer(uint8_t index, bool red, bool green, bool blue);
+#elif defined(LED_MATRIX_ENABLE)
+// LED Matrix Specific scripts
+void IS31FL_simple_set_scaling_buffer(uint8_t index, bool value);
+void IS31FL_simple_set_brightness(int index, uint8_t value);
+void IS31FL_simple_set_brigntness_all(uint8_t value);
+#endif
diff --git a/drivers/oled/oled_driver.h b/drivers/oled/oled_driver.h
index 3b56d370dc..918b837f07 100644
--- a/drivers/oled/oled_driver.h
+++ b/drivers/oled/oled_driver.h
@@ -34,16 +34,16 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
# define OLED_DISPLAY_HEIGHT 64
# endif
# ifndef OLED_MATRIX_SIZE
-# define OLED_MATRIX_SIZE (OLED_DISPLAY_HEIGHT / 8 * OLED_DISPLAY_WIDTH) // 1024 (compile time mathed)
+# define OLED_MATRIX_SIZE (OLED_DISPLAY_HEIGHT / 8 * OLED_DISPLAY_WIDTH) // 1024 (compile time mathed)
# endif
# ifndef OLED_BLOCK_TYPE
# define OLED_BLOCK_TYPE uint16_t
# endif
# ifndef OLED_BLOCK_COUNT
-# define OLED_BLOCK_COUNT (sizeof(OLED_BLOCK_TYPE) * 8) // 32 (compile time mathed)
+# define OLED_BLOCK_COUNT (sizeof(OLED_BLOCK_TYPE) * 8) // 32 (compile time mathed)
# endif
# ifndef OLED_BLOCK_SIZE
-# define OLED_BLOCK_SIZE (OLED_MATRIX_SIZE / OLED_BLOCK_COUNT) // 32 (compile time mathed)
+# define OLED_BLOCK_SIZE (OLED_MATRIX_SIZE / OLED_BLOCK_COUNT) // 32 (compile time mathed)
# endif
# ifndef OLED_COM_PINS
# define OLED_COM_PINS COM_PINS_ALT
@@ -68,7 +68,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
// If OLED_BLOCK_TYPE is uint8_t, these tables would look like:
// #define OLED_SOURCE_MAP { 0, 8, 16, 24, 32, 40, 48, 56, 64, 72, 80, 88, 96, 104, 112, 120 }
// #define OLED_TARGET_MAP { 56, 120, 48, 112, 40, 104, 32, 96, 24, 88, 16, 80, 8, 72, 0, 64 }
-#else // defined(OLED_DISPLAY_128X64)
+#else // defined(OLED_DISPLAY_128X64)
// Default 128x32
# ifndef OLED_DISPLAY_WIDTH
# define OLED_DISPLAY_WIDTH 128
@@ -77,16 +77,16 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
# define OLED_DISPLAY_HEIGHT 32
# endif
# ifndef OLED_MATRIX_SIZE
-# define OLED_MATRIX_SIZE (OLED_DISPLAY_HEIGHT / 8 * OLED_DISPLAY_WIDTH) // 512 (compile time mathed)
+# define OLED_MATRIX_SIZE (OLED_DISPLAY_HEIGHT / 8 * OLED_DISPLAY_WIDTH) // 512 (compile time mathed)
# endif
# ifndef OLED_BLOCK_TYPE
-# define OLED_BLOCK_TYPE uint16_t // Type to use for segmenting the oled display for smart rendering, use unsigned types only
+# define OLED_BLOCK_TYPE uint16_t // Type to use for segmenting the oled display for smart rendering, use unsigned types only
# endif
# ifndef OLED_BLOCK_COUNT
-# define OLED_BLOCK_COUNT (sizeof(OLED_BLOCK_TYPE) * 8) // 16 (compile time mathed)
+# define OLED_BLOCK_COUNT (sizeof(OLED_BLOCK_TYPE) * 8) // 16 (compile time mathed)
# endif
# ifndef OLED_BLOCK_SIZE
-# define OLED_BLOCK_SIZE (OLED_MATRIX_SIZE / OLED_BLOCK_COUNT) // 32 (compile time mathed)
+# define OLED_BLOCK_SIZE (OLED_MATRIX_SIZE / OLED_BLOCK_COUNT) // 32 (compile time mathed)
# endif
# ifndef OLED_COM_PINS
# define OLED_COM_PINS COM_PINS_SEQ
@@ -105,7 +105,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
// If OLED_BLOCK_TYPE is uint8_t, these tables would look like:
// #define OLED_SOURCE_MAP { 0, 8, 16, 24, 32, 40, 48, 56 }
// #define OLED_TARGET_MAP { 48, 32, 16, 0, 56, 40, 24, 8 }
-#endif // defined(OLED_DISPLAY_CUSTOM)
+#endif // defined(OLED_DISPLAY_CUSTOM)
#if !defined(OLED_IC)
# define OLED_IC OLED_IC_SSD1306
@@ -180,7 +180,7 @@ typedef enum {
OLED_ROTATION_0 = 0,
OLED_ROTATION_90 = 1,
OLED_ROTATION_180 = 2,
- OLED_ROTATION_270 = 3, // OLED_ROTATION_90 | OLED_ROTATION_180
+ OLED_ROTATION_270 = 3, // OLED_ROTATION_90 | OLED_ROTATION_180
} oled_rotation_t;
// Initialize the oled display, rotating the rendered output based on the define passed in.
@@ -262,7 +262,7 @@ void oled_write_raw_P(const char *data, uint16_t size);
# define oled_write_P(data, invert) oled_write(data, invert)
# define oled_write_ln_P(data, invert) oled_write(data, invert)
# define oled_write_raw_P(data, size) oled_write_raw(data, size)
-#endif // defined(__AVR__)
+#endif // defined(__AVR__)
// Can be used to manually turn on the screen if it is off
// Returns true if the screen was on or turns on
diff --git a/drivers/oled/ssd1306_sh1106.c b/drivers/oled/ssd1306_sh1106.c
index d9bd3c14bd..30cfeb5648 100644
--- a/drivers/oled/ssd1306_sh1106.c
+++ b/drivers/oled/ssd1306_sh1106.c
@@ -53,7 +53,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#define PAGE_ADDR 0x22
#define PAM_SETCOLUMN_LSB 0x00
#define PAM_SETCOLUMN_MSB 0x10
-#define PAM_PAGE_ADDR 0xB0 // 0xb0 -- 0xb7
+#define PAM_PAGE_ADDR 0xB0 // 0xb0 -- 0xb7
// Hardware Configuration Commands
#define DISPLAY_START_LINE 0x40
@@ -97,9 +97,9 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
#define I2C_DATA 0x40
#if defined(__AVR__)
# define I2C_TRANSMIT_P(data) i2c_transmit_P((OLED_DISPLAY_ADDRESS << 1), &data[0], sizeof(data), OLED_I2C_TIMEOUT)
-#else // defined(__AVR__)
+#else // defined(__AVR__)
# define I2C_TRANSMIT_P(data) i2c_transmit((OLED_DISPLAY_ADDRESS << 1), &data[0], sizeof(data), OLED_I2C_TIMEOUT)
-#endif // defined(__AVR__)
+#endif // defined(__AVR__)
#define I2C_TRANSMIT(data) i2c_transmit((OLED_DISPLAY_ADDRESS << 1), &data[0], sizeof(data), OLED_I2C_TIMEOUT)
#define I2C_WRITE_REG(mode, data, size) i2c_writeReg((OLED_DISPLAY_ADDRESS << 1), mode, data, size, OLED_I2C_TIMEOUT)
@@ -119,7 +119,7 @@ bool oled_inverted = false;
uint8_t oled_brightness = OLED_BRIGHTNESS;
oled_rotation_t oled_rotation = 0;
uint8_t oled_rotation_width = 0;
-uint8_t oled_scroll_speed = 0; // this holds the speed after being remapped to ssd1306 internal values
+uint8_t oled_scroll_speed = 0; // this holds the speed after being remapped to ssd1306 internal values
uint8_t oled_scroll_start = 0;
uint8_t oled_scroll_end = 7;
#if OLED_TIMEOUT > 0
@@ -190,7 +190,7 @@ bool oled_init(oled_rotation_t rotation) {
#if (OLED_IC != OLED_IC_SH1106)
// MEMORY_MODE is unsupported on SH1106 (Page Addressing only)
MEMORY_MODE,
- 0x00, // Horizontal addressing mode
+ 0x00, // Horizontal addressing mode
#endif
};
if (I2C_TRANSMIT_P(display_setup1) != I2C_STATUS_SUCCESS) {
@@ -232,8 +232,12 @@ bool oled_init(oled_rotation_t rotation) {
return true;
}
-__attribute__((weak)) oled_rotation_t oled_init_kb(oled_rotation_t rotation) { return rotation; }
-__attribute__((weak)) oled_rotation_t oled_init_user(oled_rotation_t rotation) { return rotation; }
+__attribute__((weak)) oled_rotation_t oled_init_kb(oled_rotation_t rotation) {
+ return rotation;
+}
+__attribute__((weak)) oled_rotation_t oled_init_user(oled_rotation_t rotation) {
+ return rotation;
+}
void oled_clear(void) {
memset(oled_buffer, 0, sizeof(oled_buffer));
@@ -306,9 +310,9 @@ void oled_render(void) {
// Set column & page position
static uint8_t display_start[] = {I2C_CMD, COLUMN_ADDR, 0, OLED_DISPLAY_WIDTH - 1, PAGE_ADDR, 0, OLED_DISPLAY_HEIGHT / 8 - 1};
if (!HAS_FLAGS(oled_rotation, OLED_ROTATION_90)) {
- calc_bounds(update_start, &display_start[1]); // Offset from I2C_CMD byte at the start
+ calc_bounds(update_start, &display_start[1]); // Offset from I2C_CMD byte at the start
} else {
- calc_bounds_90(update_start, &display_start[1]); // Offset from I2C_CMD byte at the start
+ calc_bounds_90(update_start, &display_start[1]); // Offset from I2C_CMD byte at the start
}
// Send column & page position
@@ -368,7 +372,8 @@ void oled_advance_page(bool clearPageRemainder) {
remaining = remaining / OLED_FONT_WIDTH;
// Write empty character until next line
- while (remaining--) oled_write_char(' ', false);
+ while (remaining--)
+ oled_write_char(' ', false);
} else {
// Next page index out of bounds?
if (index + remaining >= OLED_MATRIX_SIZE) {
@@ -419,7 +424,7 @@ void oled_write_char(const char data, bool invert) {
_Static_assert(sizeof(font) >= ((OLED_FONT_END + 1 - OLED_FONT_START) * OLED_FONT_WIDTH), "OLED_FONT_END references outside array");
// set the reder buffer data
- uint8_t cast_data = (uint8_t)data; // font based on unsigned type for index
+ uint8_t cast_data = (uint8_t)data; // font based on unsigned type for index
if (cast_data < OLED_FONT_START || cast_data > OLED_FONT_END) {
memset(oled_cursor, 0x00, OLED_FONT_WIDTH);
} else {
@@ -545,7 +550,7 @@ void oled_write_raw_P(const char *data, uint16_t size) {
oled_dirty |= ((OLED_BLOCK_TYPE)1 << (i / OLED_BLOCK_SIZE));
}
}
-#endif // defined(__AVR__)
+#endif // defined(__AVR__)
bool oled_on(void) {
if (!oled_initialized) {
@@ -595,7 +600,9 @@ bool oled_off(void) {
return !oled_active;
}
-bool is_oled_on(void) { return oled_active; }
+bool is_oled_on(void) {
+ return oled_active;
+}
uint8_t oled_set_brightness(uint8_t level) {
if (!oled_initialized) {
@@ -613,7 +620,9 @@ uint8_t oled_set_brightness(uint8_t level) {
return oled_brightness;
}
-uint8_t oled_get_brightness(void) { return oled_brightness; }
+uint8_t oled_get_brightness(void) {
+ return oled_brightness;
+}
// Set the specific 8 lines rows of the screen to scroll.
// 0 is the default for start, and 7 for end, which is the entire
@@ -693,7 +702,9 @@ bool oled_scroll_off(void) {
return !oled_scrolling;
}
-bool is_oled_scrolling(void) { return oled_scrolling; }
+bool is_oled_scrolling(void) {
+ return oled_scrolling;
+}
bool oled_invert(bool invert) {
if (!oled_initialized) {
@@ -777,5 +788,9 @@ void oled_task(void) {
#endif
}
-__attribute__((weak)) bool oled_task_kb(void) { return oled_task_user(); }
-__attribute__((weak)) bool oled_task_user(void) { return true; }
+__attribute__((weak)) bool oled_task_kb(void) {
+ return oled_task_user();
+}
+__attribute__((weak)) bool oled_task_user(void) {
+ return true;
+}
diff --git a/drivers/ps2/ps2_busywait.c b/drivers/ps2/ps2_busywait.c
index 983194eea8..c5a0183bb7 100644
--- a/drivers/ps2/ps2_busywait.c
+++ b/drivers/ps2/ps2_busywait.c
@@ -71,12 +71,12 @@ uint8_t ps2_host_send(uint8_t data) {
/* terminate a transmission if we have */
inhibit();
- wait_us(100); // 100us [4]p.13, [5]p.50
+ wait_us(100); // 100us [4]p.13, [5]p.50
/* 'Request to Send' and Start bit */
data_lo();
clock_hi();
- WAIT(clock_lo, 10000, 10); // 10ms [5]p.50
+ WAIT(clock_lo, 10000, 10); // 10ms [5]p.50
/* Data bit */
for (uint8_t i = 0; i < 8; i++) {
@@ -143,7 +143,7 @@ uint8_t ps2_host_recv(void) {
idle();
/* start bit [1] */
- WAIT(clock_lo, 100, 1); // TODO: this is enough?
+ WAIT(clock_lo, 100, 1); // TODO: this is enough?
WAIT(data_lo, 1, 2);
WAIT(clock_hi, 50, 3);
diff --git a/drivers/ps2/ps2_interrupt.c b/drivers/ps2/ps2_interrupt.c
index 70debd02f7..c49b4f8b75 100644
--- a/drivers/ps2/ps2_interrupt.c
+++ b/drivers/ps2/ps2_interrupt.c
@@ -43,7 +43,7 @@ POSSIBILITY OF SUCH DAMAGE.
#if defined(__AVR__)
# include <avr/interrupt.h>
-#elif defined(PROTOCOL_CHIBIOS) // TODO: or STM32 ?
+#elif defined(PROTOCOL_CHIBIOS) // TODO: or STM32 ?
// chibiOS headers
# include "ch.h"
# include "hal.h"
@@ -71,7 +71,9 @@ static inline void pbuf_clear(void);
#if defined(PROTOCOL_CHIBIOS)
void ps2_interrupt_service_routine(void);
-void palCallback(void *arg) { ps2_interrupt_service_routine(); }
+void palCallback(void *arg) {
+ ps2_interrupt_service_routine();
+}
# define PS2_INT_INIT() \
{ palSetLineMode(PS2_CLOCK_PIN, PAL_MODE_INPUT); } \
@@ -85,7 +87,7 @@ void palCallback(void *arg) { ps2_interrupt_service_routine(); }
# define PS2_INT_OFF() \
{ palDisableLineEvent(PS2_CLOCK_PIN); } \
while (0)
-#endif // PROTOCOL_CHIBIOS
+#endif // PROTOCOL_CHIBIOS
void ps2_host_init(void) {
idle();
@@ -103,12 +105,12 @@ uint8_t ps2_host_send(uint8_t data) {
/* terminate a transmission if we have */
inhibit();
- wait_us(100); // 100us [4]p.13, [5]p.50
+ wait_us(100); // 100us [4]p.13, [5]p.50
/* 'Request to Send' and Start bit */
data_lo();
clock_hi();
- WAIT(clock_lo, 10000, 10); // 10ms [5]p.50
+ WAIT(clock_lo, 10000, 10); // 10ms [5]p.50
/* Data bit[2-9] */
for (uint8_t i = 0; i < 8; i++) {
@@ -244,7 +246,9 @@ RETURN:
}
#if defined(__AVR__)
-ISR(PS2_INT_VECT) { ps2_interrupt_service_routine(); }
+ISR(PS2_INT_VECT) {
+ ps2_interrupt_service_routine();
+}
#endif
/* send LED state to keyboard */
diff --git a/drivers/ps2/ps2_mouse.c b/drivers/ps2/ps2_mouse.c
index 8a6668b410..ccb0a929ae 100644
--- a/drivers/ps2/ps2_mouse.c
+++ b/drivers/ps2/ps2_mouse.c
@@ -42,7 +42,7 @@ static inline void ps2_mouse_scroll_button_task(report_mouse_t *mouse_report);
void ps2_mouse_init(void) {
ps2_host_init();
- wait_ms(PS2_MOUSE_INIT_DELAY); // wait for powering up
+ wait_ms(PS2_MOUSE_INIT_DELAY); // wait for powering up
PS2_MOUSE_SEND(PS2_MOUSE_RESET, "ps2_mouse_init: sending reset");
@@ -113,9 +113,13 @@ void ps2_mouse_task(void) {
ps2_mouse_clear_report(&mouse_report);
}
-void ps2_mouse_disable_data_reporting(void) { PS2_MOUSE_SEND(PS2_MOUSE_DISABLE_DATA_REPORTING, "ps2 mouse disable data reporting"); }
+void ps2_mouse_disable_data_reporting(void) {
+ PS2_MOUSE_SEND(PS2_MOUSE_DISABLE_DATA_REPORTING, "ps2 mouse disable data reporting");
+}
-void ps2_mouse_enable_data_reporting(void) { PS2_MOUSE_SEND(PS2_MOUSE_ENABLE_DATA_REPORTING, "ps2 mouse enable data reporting"); }
+void ps2_mouse_enable_data_reporting(void) {
+ PS2_MOUSE_SEND(PS2_MOUSE_ENABLE_DATA_REPORTING, "ps2 mouse enable data reporting");
+}
void ps2_mouse_set_remote_mode(void) {
PS2_MOUSE_SEND_SAFE(PS2_MOUSE_SET_REMOTE_MODE, "ps2 mouse set remote mode");
@@ -127,13 +131,21 @@ void ps2_mouse_set_stream_mode(void) {
ps2_mouse_mode = PS2_MOUSE_STREAM_MODE;
}
-void ps2_mouse_set_scaling_2_1(void) { PS2_MOUSE_SEND_SAFE(PS2_MOUSE_SET_SCALING_2_1, "ps2 mouse set scaling 2:1"); }
+void ps2_mouse_set_scaling_2_1(void) {
+ PS2_MOUSE_SEND_SAFE(PS2_MOUSE_SET_SCALING_2_1, "ps2 mouse set scaling 2:1");
+}
-void ps2_mouse_set_scaling_1_1(void) { PS2_MOUSE_SEND_SAFE(PS2_MOUSE_SET_SCALING_1_1, "ps2 mouse set scaling 1:1"); }
+void ps2_mouse_set_scaling_1_1(void) {
+ PS2_MOUSE_SEND_SAFE(PS2_MOUSE_SET_SCALING_1_1, "ps2 mouse set scaling 1:1");
+}
-void ps2_mouse_set_resolution(ps2_mouse_resolution_t resolution) { PS2_MOUSE_SET_SAFE(PS2_MOUSE_SET_RESOLUTION, resolution, "ps2 mouse set resolution"); }
+void ps2_mouse_set_resolution(ps2_mouse_resolution_t resolution) {
+ PS2_MOUSE_SET_SAFE(PS2_MOUSE_SET_RESOLUTION, resolution, "ps2 mouse set resolution");
+}
-void ps2_mouse_set_sample_rate(ps2_mouse_sample_rate_t sample_rate) { PS2_MOUSE_SET_SAFE(PS2_MOUSE_SET_SAMPLE_RATE, sample_rate, "ps2 mouse set sample rate"); }
+void ps2_mouse_set_sample_rate(ps2_mouse_sample_rate_t sample_rate) {
+ PS2_MOUSE_SET_SAFE(PS2_MOUSE_SET_SAMPLE_RATE, sample_rate, "ps2 mouse set sample rate");
+}
/* ============================= HELPERS ============================ */
@@ -165,7 +177,7 @@ static inline void ps2_mouse_convert_report_to_hid(report_mouse_t *mouse_report)
#ifdef PS2_MOUSE_INVERT_X
mouse_report->x = -mouse_report->x;
#endif
-#ifndef PS2_MOUSE_INVERT_Y // NOTE if not!
+#ifndef PS2_MOUSE_INVERT_Y // NOTE if not!
// invert coordinate of y to conform to USB HID mouse
mouse_report->y = -mouse_report->y;
#endif
diff --git a/drivers/sensors/adns5050.c b/drivers/sensors/adns5050.c
index c23d24d5af..b76268fba2 100644
--- a/drivers/sensors/adns5050.c
+++ b/drivers/sensors/adns5050.c
@@ -74,9 +74,13 @@ void adns5050_sync(void) {
writePinHigh(ADNS5050_CS_PIN);
}
-void adns5050_cs_select(void) { writePinLow(ADNS5050_CS_PIN); }
+void adns5050_cs_select(void) {
+ writePinLow(ADNS5050_CS_PIN);
+}
-void adns5050_cs_deselect(void) { writePinHigh(ADNS5050_CS_PIN); }
+void adns5050_cs_deselect(void) {
+ writePinHigh(ADNS5050_CS_PIN);
+}
uint8_t adns5050_serial_read(void) {
setPinInput(ADNS5050_SDIO_PIN);
@@ -190,7 +194,7 @@ int8_t convert_twoscomp(uint8_t data) {
// Don't forget to use the definitions for CPI in the header file.
void adns5050_set_cpi(uint16_t cpi) {
- uint8_t cpival = constrain((cpi / 125), 0x1, 0xD); // limits to 0--119
+ uint8_t cpival = constrain((cpi / 125), 0x1, 0xD); // limits to 0--119
adns5050_write_reg(REG_MOUSE_CONTROL2, 0b10000 | cpival);
}
diff --git a/drivers/sensors/adns9800.c b/drivers/sensors/adns9800.c
index c52f991804..3633f23e52 100644
--- a/drivers/sensors/adns9800.c
+++ b/drivers/sensors/adns9800.c
@@ -77,7 +77,9 @@
#define MSB1 0x80
// clang-format on
-void adns9800_spi_start(void) { spi_start(ADNS9800_CS_PIN, false, ADNS9800_SPI_MODE, ADNS9800_SPI_DIVISOR); }
+void adns9800_spi_start(void) {
+ spi_start(ADNS9800_CS_PIN, false, ADNS9800_SPI_MODE, ADNS9800_SPI_DIVISOR);
+}
void adns9800_write(uint8_t reg_addr, uint8_t data) {
adns9800_spi_start();
@@ -135,10 +137,8 @@ void adns9800_init() {
wait_us(15);
// send all bytes of the firmware
- unsigned char c;
- for (int i = 0; i < FIRMWARE_LENGTH; i++) {
- c = (unsigned char)pgm_read_byte(adns9800_firmware_data + i);
- spi_write(c);
+ for (uint16_t i = 0; i < FIRMWARE_LENGTH; i++) {
+ spi_write(pgm_read_byte(firmware_data + i));
wait_us(15);
}
@@ -154,8 +154,8 @@ void adns9800_init() {
}
config_adns9800_t adns9800_get_config(void) {
- uint8_t config_1 = adns9800_read(REG_Configuration_I);
- return (config_adns9800_t){(config_1 & 0xFF) * CPI_STEP};
+ uint8_t cpival = adns9800_read(REG_Configuration_I);
+ return (config_adns9800_t){(cpival & 0xFF) * CPI_STEP};
}
void adns9800_set_config(config_adns9800_t config) {
@@ -164,8 +164,8 @@ void adns9800_set_config(config_adns9800_t config) {
}
uint16_t adns9800_get_cpi(void) {
- uint8_t config_1 = adns9800_read(REG_Configuration_I);
- return (uint16_t){(config_1 & 0xFF) * CPI_STEP};
+ uint8_t cpival = adns9800_read(REG_Configuration_I);
+ return (uint16_t)(cpival & 0xFF) * CPI_STEP;
}
void adns9800_set_cpi(uint16_t cpi) {
@@ -184,7 +184,7 @@ static int16_t convertDeltaToInt(uint8_t high, uint8_t low) {
}
report_adns9800_t adns9800_get_report(void) {
- report_adns9800_t report = {0, 0};
+ report_adns9800_t report = {0};
adns9800_spi_start();
diff --git a/drivers/sensors/adns9800_srom_A6.h b/drivers/sensors/adns9800_srom_A6.h
index d86ecbbd9e..e698a401b9 100644
--- a/drivers/sensors/adns9800_srom_A6.h
+++ b/drivers/sensors/adns9800_srom_A6.h
@@ -6,7 +6,7 @@
// clang-format off
-const uint8_t adns9800_firmware_data[FIRMWARE_LENGTH] PROGMEM = {
+const uint8_t firmware_data[FIRMWARE_LENGTH] PROGMEM = {
0x03, 0xA6, 0x68, 0x1E, 0x7D, 0x10, 0x7E, 0x7E, 0x5F, 0x1C, 0xB8, 0xF2, 0x47, 0x0C, 0x7B, 0x74,
0x4B, 0x14, 0x8B, 0x75, 0x66, 0x51, 0x0B, 0x8C, 0x76, 0x74, 0x4B, 0x14, 0xAA, 0xD6, 0x0F, 0x9C,
0xBA, 0xF6, 0x6E, 0x3F, 0xDD, 0x38, 0xD5, 0x02, 0x80, 0x9B, 0x82, 0x6D, 0x58, 0x13, 0xA4, 0xAB,
diff --git a/drivers/sensors/analog_joystick.c b/drivers/sensors/analog_joystick.c
index 1666bed047..95f8cff23a 100644
--- a/drivers/sensors/analog_joystick.c
+++ b/drivers/sensors/analog_joystick.c
@@ -24,7 +24,7 @@ uint16_t minAxisValue = ANALOG_JOYSTICK_AXIS_MIN;
uint16_t maxAxisValue = ANALOG_JOYSTICK_AXIS_MAX;
uint8_t maxCursorSpeed = ANALOG_JOYSTICK_SPEED_MAX;
-uint8_t speedRegulator = ANALOG_JOYSTICK_SPEED_REGULATOR; // Lower Values Create Faster Movement
+uint8_t speedRegulator = ANALOG_JOYSTICK_SPEED_REGULATOR; // Lower Values Create Faster Movement
int16_t xOrigin, yOrigin;
diff --git a/drivers/sensors/cirque_pinnacle.c b/drivers/sensors/cirque_pinnacle.c
index b807c4f076..2db7f916fe 100644
--- a/drivers/sensors/cirque_pinnacle.c
+++ b/drivers/sensors/cirque_pinnacle.c
@@ -54,7 +54,9 @@ void RAP_ReadBytes(uint8_t address, uint8_t* data, uint8_t count);
void RAP_Write(uint8_t address, uint8_t data);
#ifdef CONSOLE_ENABLE
-void print_byte(uint8_t byte) { xprintf("%c%c%c%c%c%c%c%c|", (byte & 0x80 ? '1' : '0'), (byte & 0x40 ? '1' : '0'), (byte & 0x20 ? '1' : '0'), (byte & 0x10 ? '1' : '0'), (byte & 0x08 ? '1' : '0'), (byte & 0x04 ? '1' : '0'), (byte & 0x02 ? '1' : '0'), (byte & 0x01 ? '1' : '0')); }
+void print_byte(uint8_t byte) {
+ xprintf("%c%c%c%c%c%c%c%c|", (byte & 0x80 ? '1' : '0'), (byte & 0x40 ? '1' : '0'), (byte & 0x20 ? '1' : '0'), (byte & 0x10 ? '1' : '0'), (byte & 0x08 ? '1' : '0'), (byte & 0x04 ? '1' : '0'), (byte & 0x02 ? '1' : '0'), (byte & 0x01 ? '1' : '0'));
+}
#endif
/* Logical Scaling Functions */
@@ -73,8 +75,12 @@ void ClipCoordinates(pinnacle_data_t* coordinates) {
}
}
-uint16_t cirque_pinnacle_get_scale(void) { return scale_data; }
-void cirque_pinnacle_set_scale(uint16_t scale) { scale_data = scale; }
+uint16_t cirque_pinnacle_get_scale(void) {
+ return scale_data;
+}
+void cirque_pinnacle_set_scale(uint16_t scale) {
+ scale_data = scale;
+}
// Scales data to desired X & Y resolution
void cirque_pinnacle_scale_data(pinnacle_data_t* coordinates, uint16_t xResolution, uint16_t yResolution) {
@@ -105,13 +111,13 @@ void cirque_pinnacle_clear_flags() {
void cirque_pinnacle_enable_feed(bool feedEnable) {
uint8_t temp;
- RAP_ReadBytes(FEEDCONFIG_1, &temp, 1); // Store contents of FeedConfig1 register
+ RAP_ReadBytes(FEEDCONFIG_1, &temp, 1); // Store contents of FeedConfig1 register
if (feedEnable) {
- temp |= 0x01; // Set Feed Enable bit
+ temp |= 0x01; // Set Feed Enable bit
RAP_Write(0x04, temp);
} else {
- temp &= ~0x01; // Clear Feed Enable bit
+ temp &= ~0x01; // Clear Feed Enable bit
RAP_Write(0x04, temp);
}
}
@@ -122,13 +128,13 @@ void cirque_pinnacle_enable_feed(bool feedEnable) {
void ERA_ReadBytes(uint16_t address, uint8_t* data, uint16_t count) {
uint8_t ERAControlValue = 0xFF;
- cirque_pinnacle_enable_feed(false); // Disable feed
+ cirque_pinnacle_enable_feed(false); // Disable feed
- RAP_Write(ERA_HIGH_BYTE, (uint8_t)(address >> 8)); // Send upper byte of ERA address
- RAP_Write(ERA_LOW_BYTE, (uint8_t)(address & 0x00FF)); // Send lower byte of ERA address
+ RAP_Write(ERA_HIGH_BYTE, (uint8_t)(address >> 8)); // Send upper byte of ERA address
+ RAP_Write(ERA_LOW_BYTE, (uint8_t)(address & 0x00FF)); // Send lower byte of ERA address
for (uint16_t i = 0; i < count; i++) {
- RAP_Write(ERA_CONTROL, 0x05); // Signal ERA-read (auto-increment) to Pinnacle
+ RAP_Write(ERA_CONTROL, 0x05); // Signal ERA-read (auto-increment) to Pinnacle
// Wait for status register 0x1E to clear
do {
@@ -145,14 +151,14 @@ void ERA_ReadBytes(uint16_t address, uint8_t* data, uint16_t count) {
void ERA_WriteByte(uint16_t address, uint8_t data) {
uint8_t ERAControlValue = 0xFF;
- cirque_pinnacle_enable_feed(false); // Disable feed
+ cirque_pinnacle_enable_feed(false); // Disable feed
- RAP_Write(ERA_VALUE, data); // Send data byte to be written
+ RAP_Write(ERA_VALUE, data); // Send data byte to be written
- RAP_Write(ERA_HIGH_BYTE, (uint8_t)(address >> 8)); // Upper byte of ERA address
- RAP_Write(ERA_LOW_BYTE, (uint8_t)(address & 0x00FF)); // Lower byte of ERA address
+ RAP_Write(ERA_HIGH_BYTE, (uint8_t)(address >> 8)); // Upper byte of ERA address
+ RAP_Write(ERA_LOW_BYTE, (uint8_t)(address & 0x00FF)); // Lower byte of ERA address
- RAP_Write(ERA_CONTROL, 0x02); // Signal an ERA-write to Pinnacle
+ RAP_Write(ERA_CONTROL, 0x02); // Signal an ERA-write to Pinnacle
// Wait for status register 0x1E to clear
do {
@@ -166,7 +172,7 @@ void cirque_pinnacle_set_adc_attenuation(uint8_t adcGain) {
uint8_t temp = 0x00;
ERA_ReadBytes(0x0187, &temp, 1);
- temp &= 0x3F; // clear top two bits
+ temp &= 0x3F; // clear top two bits
temp |= adcGain;
ERA_WriteByte(0x0187, temp);
ERA_ReadBytes(0x0187, &temp, 1);
diff --git a/drivers/sensors/cirque_pinnacle.h b/drivers/sensors/cirque_pinnacle.h
index db891122a6..c8cb360e03 100644
--- a/drivers/sensors/cirque_pinnacle.h
+++ b/drivers/sensors/cirque_pinnacle.h
@@ -26,16 +26,16 @@ void cirque_pinnacle_set_scale(uint16_t scale);
// Coordinate scaling values
#ifndef CIRQUE_PINNACLE_X_LOWER
-# define CIRQUE_PINNACLE_X_LOWER 127 // min "reachable" X value
+# define CIRQUE_PINNACLE_X_LOWER 127 // min "reachable" X value
#endif
#ifndef CIRQUE_PINNACLE_X_UPPER
-# define CIRQUE_PINNACLE_X_UPPER 1919 // max "reachable" X value
+# define CIRQUE_PINNACLE_X_UPPER 1919 // max "reachable" X value
#endif
#ifndef CIRQUE_PINNACLE_Y_LOWER
-# define CIRQUE_PINNACLE_Y_LOWER 63 // min "reachable" Y value
+# define CIRQUE_PINNACLE_Y_LOWER 63 // min "reachable" Y value
#endif
#ifndef CIRQUE_PINNACLE_Y_UPPER
-# define CIRQUE_PINNACLE_Y_UPPER 1471 // max "reachable" Y value
+# define CIRQUE_PINNACLE_Y_UPPER 1471 // max "reachable" Y value
#endif
#ifndef CIRQUE_PINNACLE_X_RANGE
# define CIRQUE_PINNACLE_X_RANGE (CIRQUE_PINNACLE_X_UPPER - CIRQUE_PINNACLE_X_LOWER)
diff --git a/drivers/sensors/cirque_pinnacle_i2c.c b/drivers/sensors/cirque_pinnacle_i2c.c
index 81dd982b0c..8a38f1dcea 100644
--- a/drivers/sensors/cirque_pinnacle_i2c.c
+++ b/drivers/sensors/cirque_pinnacle_i2c.c
@@ -14,7 +14,7 @@ extern bool touchpad_init;
/* RAP Functions */
// Reads <count> Pinnacle registers starting at <address>
void RAP_ReadBytes(uint8_t address, uint8_t* data, uint8_t count) {
- uint8_t cmdByte = READ_MASK | address; // Form the READ command byte
+ uint8_t cmdByte = READ_MASK | address; // Form the READ command byte
if (touchpad_init) {
i2c_writeReg(CIRQUE_PINNACLE_ADDR << 1, cmdByte, NULL, 0, CIRQUE_PINNACLE_TIMEOUT);
if (i2c_readReg(CIRQUE_PINNACLE_ADDR << 1, cmdByte, data, count, CIRQUE_PINNACLE_TIMEOUT) != I2C_STATUS_SUCCESS) {
@@ -29,7 +29,7 @@ void RAP_ReadBytes(uint8_t address, uint8_t* data, uint8_t count) {
// Writes single-byte <data> to <address>
void RAP_Write(uint8_t address, uint8_t data) {
- uint8_t cmdByte = WRITE_MASK | address; // Form the WRITE command byte
+ uint8_t cmdByte = WRITE_MASK | address; // Form the WRITE command byte
if (touchpad_init) {
if (i2c_writeReg(CIRQUE_PINNACLE_ADDR << 1, cmdByte, &data, sizeof(data), CIRQUE_PINNACLE_TIMEOUT) != I2C_STATUS_SUCCESS) {
diff --git a/drivers/sensors/cirque_pinnacle_spi.c b/drivers/sensors/cirque_pinnacle_spi.c
index ed40abd9fa..e00e73eb8c 100644
--- a/drivers/sensors/cirque_pinnacle_spi.c
+++ b/drivers/sensors/cirque_pinnacle_spi.c
@@ -13,14 +13,14 @@ extern bool touchpad_init;
/* RAP Functions */
// Reads <count> Pinnacle registers starting at <address>
void RAP_ReadBytes(uint8_t address, uint8_t* data, uint8_t count) {
- uint8_t cmdByte = READ_MASK | address; // Form the READ command byte
+ uint8_t cmdByte = READ_MASK | address; // Form the READ command byte
if (touchpad_init) {
if (spi_start(CIRQUE_PINNACLE_SPI_CS_PIN, CIRQUE_PINNACLE_SPI_LSBFIRST, CIRQUE_PINNACLE_SPI_MODE, CIRQUE_PINNACLE_SPI_DIVISOR)) {
spi_write(cmdByte);
- spi_read(); // filler
- spi_read(); // filler
+ spi_read(); // filler
+ spi_read(); // filler
for (uint8_t i = 0; i < count; i++) {
- data[i] = spi_read(); // each sepsequent read gets another register's contents
+ data[i] = spi_read(); // each sepsequent read gets another register's contents
}
} else {
#ifdef CONSOLE_ENABLE
@@ -34,7 +34,7 @@ void RAP_ReadBytes(uint8_t address, uint8_t* data, uint8_t count) {
// Writes single-byte <data> to <address>
void RAP_Write(uint8_t address, uint8_t data) {
- uint8_t cmdByte = WRITE_MASK | address; // Form the WRITE command byte
+ uint8_t cmdByte = WRITE_MASK | address; // Form the WRITE command byte
if (touchpad_init) {
if (spi_start(CIRQUE_PINNACLE_SPI_CS_PIN, CIRQUE_PINNACLE_SPI_LSBFIRST, CIRQUE_PINNACLE_SPI_MODE, CIRQUE_PINNACLE_SPI_DIVISOR)) {
diff --git a/drivers/sensors/pimoroni_trackball.c b/drivers/sensors/pimoroni_trackball.c
index 7d390056ea..333e017a06 100644
--- a/drivers/sensors/pimoroni_trackball.c
+++ b/drivers/sensors/pimoroni_trackball.c
@@ -33,8 +33,26 @@
static uint16_t precision = 128;
-float pimoroni_trackball_get_precision(void) { return ((float)precision / 128); }
-void pimoroni_trackball_set_precision(float floatprecision) { precision = (floatprecision * 128); }
+uint16_t pimoroni_trackball_get_cpi(void) {
+ return (precision * 125);
+}
+/**
+ * @brief Sets the scaling value for pimoroni trackball
+ *
+ * Sets a scaling value for pimoroni trackball to allow runtime adjustment. This isn't used by the sensor and is an
+ * approximation so the functions are consistent across drivers.
+ *
+ * NOTE: This rounds down to the nearest number divisable by 125 that's a positive integer, values below 125 are clamped to 125.
+ *
+ * @param cpi uint16_t
+ */
+void pimoroni_trackball_set_cpi(uint16_t cpi) {
+ if (cpi < 249) {
+ precision = 1;
+ } else {
+ precision = (cpi - (cpi % 125)) / 125;
+ }
+}
void pimoroni_trackball_set_rgbw(uint8_t r, uint8_t g, uint8_t b, uint8_t w) {
uint8_t data[4] = {r, g, b, w};
@@ -60,7 +78,7 @@ i2c_status_t read_pimoroni_trackball(pimoroni_data_t* data) {
return status;
}
-__attribute__((weak)) void pimironi_trackball_device_init(void) {
+__attribute__((weak)) void pimoroni_trackball_device_init(void) {
i2c_init();
pimoroni_trackball_set_rgbw(0x00, 0x00, 0x00, 0x00);
}
diff --git a/drivers/sensors/pimoroni_trackball.h b/drivers/sensors/pimoroni_trackball.h
index 59ee8724ba..e20ee748a7 100644
--- a/drivers/sensors/pimoroni_trackball.h
+++ b/drivers/sensors/pimoroni_trackball.h
@@ -23,9 +23,6 @@
#ifndef PIMORONI_TRACKBALL_ADDRESS
# define PIMORONI_TRACKBALL_ADDRESS 0x0A
#endif
-#ifndef PIMORONI_TRACKBALL_INTERVAL_MS
-# define PIMORONI_TRACKBALL_INTERVAL_MS 8
-#endif
#ifndef PIMORONI_TRACKBALL_SCALE
# define PIMORONI_TRACKBALL_SCALE 5
#endif
@@ -52,10 +49,10 @@ typedef struct {
uint8_t click;
} pimoroni_data_t;
-void pimironi_trackball_device_init(void);
+void pimoroni_trackball_device_init(void);
void pimoroni_trackball_set_rgbw(uint8_t red, uint8_t green, uint8_t blue, uint8_t white);
int16_t pimoroni_trackball_get_offsets(uint8_t negative_dir, uint8_t positive_dir, uint8_t scale);
void pimoroni_trackball_adapt_values(int8_t* mouse, int16_t* offset);
-float pimoroni_trackball_get_precision(void);
-void pimoroni_trackball_set_precision(float precision);
+uint16_t pimoroni_trackball_get_cpi(void);
+void pimoroni_trackball_set_cpi(uint16_t cpi);
i2c_status_t read_pimoroni_trackball(pimoroni_data_t* data);
diff --git a/drivers/sensors/pmw3360.c b/drivers/sensors/pmw3360.c
index 50d1c35801..8c977be1c8 100644
--- a/drivers/sensors/pmw3360.c
+++ b/drivers/sensors/pmw3360.c
@@ -16,136 +16,126 @@
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
+#include "spi_master.h"
#include "pmw3360.h"
#include "wait.h"
#include "debug.h"
#include "print.h"
-#include PMW3360_FIRMWARE_H
+#include "pmw3360_firmware.h"
// Registers
// clang-format off
-#define REG_Product_ID 0x00
-#define REG_Revision_ID 0x01
-#define REG_Motion 0x02
-#define REG_Delta_X_L 0x03
-#define REG_Delta_X_H 0x04
-#define REG_Delta_Y_L 0x05
-#define REG_Delta_Y_H 0x06
-#define REG_SQUAL 0x07
-#define REG_Raw_Data_Sum 0x08
-#define REG_Maximum_Raw_data 0x09
-#define REG_Minimum_Raw_data 0x0A
-#define REG_Shutter_Lower 0x0B
-#define REG_Shutter_Upper 0x0C
-#define REG_Control 0x0D
-#define REG_Config1 0x0F
-#define REG_Config2 0x10
-#define REG_Angle_Tune 0x11
-#define REG_Frame_Capture 0x12
-#define REG_SROM_Enable 0x13
-#define REG_Run_Downshift 0x14
-#define REG_Rest1_Rate_Lower 0x15
-#define REG_Rest1_Rate_Upper 0x16
-#define REG_Rest1_Downshift 0x17
-#define REG_Rest2_Rate_Lower 0x18
-#define REG_Rest2_Rate_Upper 0x19
-#define REG_Rest2_Downshift 0x1A
-#define REG_Rest3_Rate_Lower 0x1B
-#define REG_Rest3_Rate_Upper 0x1C
-#define REG_Observation 0x24
-#define REG_Data_Out_Lower 0x25
-#define REG_Data_Out_Upper 0x26
-#define REG_Raw_Data_Dump 0x29
-#define REG_SROM_ID 0x2A
-#define REG_Min_SQ_Run 0x2B
-#define REG_Raw_Data_Threshold 0x2C
-#define REG_Config5 0x2F
-#define REG_Power_Up_Reset 0x3A
-#define REG_Shutdown 0x3B
-#define REG_Inverse_Product_ID 0x3F
-#define REG_LiftCutoff_Tune3 0x41
-#define REG_Angle_Snap 0x42
-#define REG_LiftCutoff_Tune1 0x4A
-#define REG_Motion_Burst 0x50
-#define REG_LiftCutoff_Tune_Timeout 0x58
-#define REG_LiftCutoff_Tune_Min_Length 0x5A
-#define REG_SROM_Load_Burst 0x62
-#define REG_Lift_Config 0x63
-#define REG_Raw_Data_Burst 0x64
-#define REG_LiftCutoff_Tune2 0x65
+#define REG_Product_ID 0x00
+#define REG_Revision_ID 0x01
+#define REG_Motion 0x02
+#define REG_Delta_X_L 0x03
+#define REG_Delta_X_H 0x04
+#define REG_Delta_Y_L 0x05
+#define REG_Delta_Y_H 0x06
+#define REG_SQUAL 0x07
+#define REG_Raw_Data_Sum 0x08
+#define REG_Maximum_Raw_data 0x09
+#define REG_Minimum_Raw_data 0x0a
+#define REG_Shutter_Lower 0x0b
+#define REG_Shutter_Upper 0x0c
+#define REG_Control 0x0d
+#define REG_Config1 0x0f
+#define REG_Config2 0x10
+#define REG_Angle_Tune 0x11
+#define REG_Frame_Capture 0x12
+#define REG_SROM_Enable 0x13
+#define REG_Run_Downshift 0x14
+#define REG_Rest1_Rate_Lower 0x15
+#define REG_Rest1_Rate_Upper 0x16
+#define REG_Rest1_Downshift 0x17
+#define REG_Rest2_Rate_Lower 0x18
+#define REG_Rest2_Rate_Upper 0x19
+#define REG_Rest2_Downshift 0x1a
+#define REG_Rest3_Rate_Lower 0x1b
+#define REG_Rest3_Rate_Upper 0x1c
+#define REG_Observation 0x24
+#define REG_Data_Out_Lower 0x25
+#define REG_Data_Out_Upper 0x26
+#define REG_Raw_Data_Dump 0x29
+#define REG_SROM_ID 0x2a
+#define REG_Min_SQ_Run 0x2b
+#define REG_Raw_Data_Threshold 0x2c
+#define REG_Config5 0x2f
+#define REG_Power_Up_Reset 0x3a
+#define REG_Shutdown 0x3b
+#define REG_Inverse_Product_ID 0x3f
+#define REG_LiftCutoff_Tune3 0x41
+#define REG_Angle_Snap 0x42
+#define REG_LiftCutoff_Tune1 0x4a
+#define REG_Motion_Burst 0x50
+#define REG_LiftCutoff_Tune_Timeout 0x58
+#define REG_LiftCutoff_Tune_Min_Length 0x5a
+#define REG_SROM_Load_Burst 0x62
+#define REG_Lift_Config 0x63
+#define REG_Raw_Data_Burst 0x64
+#define REG_LiftCutoff_Tune2 0x65
+
+#define CPI_STEP 100
// clang-format on
+// limits to 0--119, resulting in a CPI range of 100 -- 12000 (as only steps of 100 are possible).
#ifndef MAX_CPI
-# define MAX_CPI 0x77 // limits to 0--119, should be max cpi/100
+# define MAX_CPI 0x77
#endif
bool _inBurst = false;
#ifdef CONSOLE_ENABLE
-void print_byte(uint8_t byte) { dprintf("%c%c%c%c%c%c%c%c|", (byte & 0x80 ? '1' : '0'), (byte & 0x40 ? '1' : '0'), (byte & 0x20 ? '1' : '0'), (byte & 0x10 ? '1' : '0'), (byte & 0x08 ? '1' : '0'), (byte & 0x04 ? '1' : '0'), (byte & 0x02 ? '1' : '0'), (byte & 0x01 ? '1' : '0')); }
+void print_byte(uint8_t byte) {
+ dprintf("%c%c%c%c%c%c%c%c|", (byte & 0x80 ? '1' : '0'), (byte & 0x40 ? '1' : '0'), (byte & 0x20 ? '1' : '0'), (byte & 0x10 ? '1' : '0'), (byte & 0x08 ? '1' : '0'), (byte & 0x04 ? '1' : '0'), (byte & 0x02 ? '1' : '0'), (byte & 0x01 ? '1' : '0'));
+}
#endif
#define constrain(amt, low, high) ((amt) < (low) ? (low) : ((amt) > (high) ? (high) : (amt)))
-bool spi_start_adv(void) {
+bool pmw3360_spi_start(void) {
bool status = spi_start(PMW3360_CS_PIN, PMW3360_SPI_LSBFIRST, PMW3360_SPI_MODE, PMW3360_SPI_DIVISOR);
+ // tNCS-SCLK, 120ns
wait_us(1);
return status;
}
-void spi_stop_adv(void) {
- wait_us(1);
- spi_stop();
-}
+spi_status_t pmw3360_write(uint8_t reg_addr, uint8_t data) {
+ pmw3360_spi_start();
-spi_status_t spi_write_adv(uint8_t reg_addr, uint8_t data) {
if (reg_addr != REG_Motion_Burst) {
_inBurst = false;
}
- spi_start_adv();
// send address of the register, with MSBit = 1 to indicate it's a write
spi_status_t status = spi_write(reg_addr | 0x80);
status = spi_write(data);
- // tSCLK-NCS for write operation
- wait_us(20);
-
- // tSWW/tSWR (=120us) minus tSCLK-NCS. Could be shortened, but is looks like a safe lower bound
- wait_us(100);
+ // tSCLK-NCS for write operation is 35us
+ wait_us(35);
spi_stop();
+
+ // tSWW/tSWR (=180us) minus tSCLK-NCS. Could be shortened, but is looks like a safe lower bound
+ wait_us(145);
return status;
}
-uint8_t spi_read_adv(uint8_t reg_addr) {
- spi_start_adv();
+uint8_t pmw3360_read(uint8_t reg_addr) {
+ pmw3360_spi_start();
// send adress of the register, with MSBit = 0 to indicate it's a read
spi_write(reg_addr & 0x7f);
-
+ // tSRAD (=160us)
+ wait_us(160);
uint8_t data = spi_read();
// tSCLK-NCS for read operation is 120ns
wait_us(1);
+ spi_stop();
// tSRW/tSRR (=20us) minus tSCLK-NCS
wait_us(19);
-
- spi_stop();
return data;
}
-void pmw3360_set_cpi(uint16_t cpi) {
- uint8_t cpival = constrain((cpi / 100) - 1, 0, MAX_CPI);
-
- spi_start_adv();
- spi_write_adv(REG_Config1, cpival);
- spi_stop();
-}
-
-uint16_t pmw3360_get_cpi(void) {
- uint8_t cpival = spi_read_adv(REG_Config1);
- return (uint16_t)((cpival + 1) & 0xFF) * 100;
-}
-
bool pmw3360_init(void) {
setPinOutput(PMW3360_CS_PIN);
@@ -153,42 +143,51 @@ bool pmw3360_init(void) {
_inBurst = false;
spi_stop();
- spi_start_adv();
+ pmw3360_spi_start();
spi_stop();
- spi_write_adv(REG_Shutdown, 0xb6); // Shutdown first
+ pmw3360_write(REG_Shutdown, 0xb6); // Shutdown first
wait_ms(300);
- spi_start_adv();
+ pmw3360_spi_start();
wait_us(40);
- spi_stop_adv();
+ spi_stop();
wait_us(40);
- spi_write_adv(REG_Power_Up_Reset, 0x5a);
+ // power up, need to first drive NCS high then low, see above.
+ pmw3360_write(REG_Power_Up_Reset, 0x5a);
wait_ms(50);
- spi_read_adv(REG_Motion);
- spi_read_adv(REG_Delta_X_L);
- spi_read_adv(REG_Delta_X_H);
- spi_read_adv(REG_Delta_Y_L);
- spi_read_adv(REG_Delta_Y_H);
+ // read registers and discard
+ pmw3360_read(REG_Motion);
+ pmw3360_read(REG_Delta_X_L);
+ pmw3360_read(REG_Delta_X_H);
+ pmw3360_read(REG_Delta_Y_L);
+ pmw3360_read(REG_Delta_Y_H);
pmw3360_upload_firmware();
- spi_stop_adv();
+ spi_stop();
wait_ms(10);
pmw3360_set_cpi(PMW3360_CPI);
wait_ms(1);
- spi_write_adv(REG_Config2, 0x00);
+ pmw3360_write(REG_Config2, 0x00);
- spi_write_adv(REG_Angle_Tune, constrain(ROTATIONAL_TRANSFORM_ANGLE, -30, 30));
+ pmw3360_write(REG_Angle_Tune, constrain(ROTATIONAL_TRANSFORM_ANGLE, -127, 127));
- spi_write_adv(REG_Lift_Config, PMW3360_LIFTOFF_DISTANCE);
+ pmw3360_write(REG_Lift_Config, PMW3360_LIFTOFF_DISTANCE);
bool init_success = pmw3360_check_signature();
+#ifdef CONSOLE_ENABLE
+ if (init_success) {
+ dprintf("pmw3360 signature verified");
+ } else {
+ dprintf("pmw3360 signature verification failed!");
+ }
+#endif
writePinLow(PMW3360_CS_PIN);
@@ -196,86 +195,94 @@ bool pmw3360_init(void) {
}
void pmw3360_upload_firmware(void) {
- spi_write_adv(REG_SROM_Enable, 0x1d);
+ // Datasheet claims we need to disable REST mode first, but during startup
+ // it's already disabled and we're not turning it on ...
+ // pmw3360_write(REG_Config2, 0x00); // disable REST mode
+ pmw3360_write(REG_SROM_Enable, 0x1d);
wait_ms(10);
- spi_write_adv(REG_SROM_Enable, 0x18);
+ pmw3360_write(REG_SROM_Enable, 0x18);
- spi_start_adv();
+ pmw3360_spi_start();
spi_write(REG_SROM_Load_Burst | 0x80);
wait_us(15);
- unsigned char c;
- for (int i = 0; i < FIRMWARE_LENGTH; i++) {
- c = (unsigned char)pgm_read_byte(firmware_data + i);
- spi_write(c);
+ for (uint16_t i = 0; i < FIRMWARE_LENGTH; i++) {
+ spi_write(pgm_read_byte(firmware_data + i));
+#ifndef PMW3360_FIRMWARE_UPLOAD_FAST
wait_us(15);
+#endif
}
wait_us(200);
- spi_read_adv(REG_SROM_ID);
+ pmw3360_read(REG_SROM_ID);
+ pmw3360_write(REG_Config2, 0x00);
+}
- spi_write_adv(REG_Config2, 0x00);
+bool pmw3360_check_signature(void) {
+ uint8_t pid = pmw3360_read(REG_Product_ID);
+ uint8_t iv_pid = pmw3360_read(REG_Inverse_Product_ID);
+ uint8_t SROM_ver = pmw3360_read(REG_SROM_ID);
+ return (pid == firmware_signature[0] && iv_pid == firmware_signature[1] && SROM_ver == firmware_signature[2]); // signature for SROM 0x04
+}
- spi_stop();
- wait_ms(10);
+uint16_t pmw3360_get_cpi(void) {
+ uint8_t cpival = pmw3360_read(REG_Config1);
+ return (uint16_t)((cpival + 1) & 0xFF) * CPI_STEP;
}
-bool pmw3360_check_signature(void) {
- uint8_t pid = spi_read_adv(REG_Product_ID);
- uint8_t iv_pid = spi_read_adv(REG_Inverse_Product_ID);
- uint8_t SROM_ver = spi_read_adv(REG_SROM_ID);
- return (pid == firmware_signature[0] && iv_pid == firmware_signature[1] && SROM_ver == firmware_signature[2]); // signature for SROM 0x04
+void pmw3360_set_cpi(uint16_t cpi) {
+ uint8_t cpival = constrain((cpi / CPI_STEP) - 1, 0, MAX_CPI);
+ pmw3360_write(REG_Config1, cpival);
}
report_pmw3360_t pmw3360_read_burst(void) {
+ report_pmw3360_t report = {0};
+
if (!_inBurst) {
#ifdef CONSOLE_ENABLE
dprintf("burst on");
#endif
- spi_write_adv(REG_Motion_Burst, 0x00);
+ pmw3360_write(REG_Motion_Burst, 0x00);
_inBurst = true;
}
- spi_start_adv();
+ pmw3360_spi_start();
spi_write(REG_Motion_Burst);
- wait_us(35); // waits for tSRAD
+ wait_us(35); // waits for tSRAD_MOTBR
- report_pmw3360_t data = {0};
+ report.motion = spi_read();
+ spi_read(); // skip Observation
+ // delta registers
+ report.dx = spi_read();
+ report.mdx = spi_read();
+ report.dy = spi_read();
+ report.mdy = spi_read();
- data.motion = spi_read();
- spi_write(0x00); // skip Observation
- data.dx = spi_read();
- data.mdx = spi_read();
- data.dy = spi_read();
- data.mdy = spi_read();
+ if (report.motion & 0b111) { // panic recovery, sometimes burst mode works weird.
+ _inBurst = false;
+ }
spi_stop();
#ifdef CONSOLE_ENABLE
if (debug_mouse) {
- print_byte(data.motion);
- print_byte(data.dx);
- print_byte(data.mdx);
- print_byte(data.dy);
- print_byte(data.mdy);
+ print_byte(report.motion);
+ print_byte(report.dx);
+ print_byte(report.mdx);
+ print_byte(report.dy);
+ print_byte(report.mdy);
dprintf("\n");
}
#endif
- data.isMotion = (data.motion & 0x80) != 0;
- data.isOnSurface = (data.motion & 0x08) == 0;
- data.dx |= (data.mdx << 8);
- data.dx = data.dx * -1;
- data.dy |= (data.mdy << 8);
- data.dy = data.dy * -1;
-
- spi_stop();
+ report.isMotion = (report.motion & 0x80) != 0;
+ report.isOnSurface = (report.motion & 0x08) == 0;
+ report.dx |= (report.mdx << 8);
+ report.dx = report.dx * -1;
+ report.dy |= (report.mdy << 8);
+ report.dy = report.dy * -1;
- if (data.motion & 0b111) { // panic recovery, sometimes burst mode works weird.
- _inBurst = false;
- }
-
- return data;
+ return report;
}
diff --git a/drivers/sensors/pmw3360.h b/drivers/sensors/pmw3360.h
index 9aa8e13f8e..eec7295871 100644
--- a/drivers/sensors/pmw3360.h
+++ b/drivers/sensors/pmw3360.h
@@ -19,8 +19,6 @@
#pragma once
#include <stdint.h>
-#include "report.h"
-#include "spi_master.h"
#ifndef PMW3360_CPI
# define PMW3360_CPI 1600
@@ -58,41 +56,20 @@
# error "No chip select pin defined -- missing PMW3360_CS_PIN"
#endif
-/*
-The pmw33660 and pmw3389 use the same registers and timing and such.
-The only differences between the two is the firmware used, and the
-range for the DPI. So add a semi-secret hack to allow use of the
-pmw3389's firmware blob. Also, can set the max cpi range too.
-This should work for the 3390 and 3391 too, in theory.
-*/
-#ifndef PMW3360_FIRMWARE_H
-# define PMW3360_FIRMWARE_H "pmw3360_firmware.h"
-#endif
-
-#ifdef CONSOLE_ENABLE
-void print_byte(uint8_t byte);
-#endif
-
typedef struct {
int8_t motion;
- bool isMotion; // True if a motion is detected.
- bool isOnSurface; // True when a chip is on a surface
- int16_t dx; // displacement on x directions. Unit: Count. (CPI * Count = Inch value)
+ bool isMotion; // True if a motion is detected.
+ bool isOnSurface; // True when a chip is on a surface
+ int16_t dx; // displacement on x directions. Unit: Count. (CPI * Count = Inch value)
int8_t mdx;
- int16_t dy; // displacement on y directions.
+ int16_t dy; // displacement on y directions.
int8_t mdy;
} report_pmw3360_t;
-bool spi_start_adv(void);
-void spi_stop_adv(void);
-spi_status_t spi_write_adv(uint8_t reg_addr, uint8_t data);
-uint8_t spi_read_adv(uint8_t reg_addr);
-bool pmw3360_init(void);
-void pmw3360_set_cpi(uint16_t cpi);
-uint16_t pmw3360_get_cpi(void);
-void pmw3360_upload_firmware(void);
-bool pmw3360_check_signature(void);
+bool pmw3360_init(void);
+void pmw3360_upload_firmware(void);
+bool pmw3360_check_signature(void);
+uint16_t pmw3360_get_cpi(void);
+void pmw3360_set_cpi(uint16_t cpi);
+/* Reads and clears the current delta values on the sensor */
report_pmw3360_t pmw3360_read_burst(void);
-
-#define degToRad(angleInDegrees) ((angleInDegrees)*M_PI / 180.0)
-#define radToDeg(angleInRadians) ((angleInRadians)*180.0 / M_PI)
diff --git a/drivers/sensors/pmw3389.c b/drivers/sensors/pmw3389.c
new file mode 100644
index 0000000000..828dafa134
--- /dev/null
+++ b/drivers/sensors/pmw3389.c
@@ -0,0 +1,294 @@
+/* Copyright 2020 Christopher Courtney, aka Drashna Jael're (@drashna) <drashna@live.com>
+ * Copyright 2019 Sunjun Kim
+ * Copyright 2020 Ploopy Corporation
+ *
+ * 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 2 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 "spi_master.h"
+#include "pmw3389.h"
+#include "wait.h"
+#include "debug.h"
+#include "print.h"
+#include "pmw3389_firmware.h"
+
+// Registers
+// clang-format off
+#define REG_Product_ID 0x00
+#define REG_Revision_ID 0x01
+#define REG_Motion 0x02
+#define REG_Delta_X_L 0x03
+#define REG_Delta_X_H 0x04
+#define REG_Delta_Y_L 0x05
+#define REG_Delta_Y_H 0x06
+#define REG_SQUAL 0x07
+#define REG_RawData_Sum 0x08
+#define REG_Maximum_RawData 0x09
+#define REG_Minimum_RawData 0x0a
+#define REG_Shutter_Lower 0x0b
+#define REG_Shutter_Upper 0x0c
+#define REG_Ripple_Control 0x0d
+#define REG_Resolution_L 0x0e
+#define REG_Resolution_H 0x0f
+#define REG_Config2 0x10
+#define REG_Angle_Tune 0x11
+#define REG_Frame_Capture 0x12
+#define REG_SROM_Enable 0x13
+#define REG_Run_Downshift 0x14
+#define REG_Rest1_Rate_Lower 0x15
+#define REG_Rest1_Rate_Upper 0x16
+#define REG_Rest1_Downshift 0x17
+#define REG_Rest2_Rate_Lower 0x18
+#define REG_Rest2_Rate_Upper 0x19
+#define REG_Rest2_Downshift 0x1a
+#define REG_Rest3_Rate_Lower 0x1b
+#define REG_Rest3_Rate_Upper 0x1c
+#define REG_Observation 0x24
+#define REG_Data_Out_Lower 0x25
+#define REG_Data_Out_Upper 0x26
+#define REG_SROM_ID 0x2a
+#define REG_Min_SQ_Run 0x2b
+#define REG_RawData_Threshold 0x2c
+#define REG_Control2 0x2d
+#define REG_Config5_L 0x2e
+#define REG_Config5_H 0x2f
+#define REG_Power_Up_Reset 0X3a
+#define REG_Shutdown 0x3b
+#define REG_Inverse_Product_ID 0x3f
+#define REG_LiftCutoff_Cal3 0x41
+#define REG_Angle_Snap 0x42
+#define REG_LiftCutoff_Cal1 0x4a
+#define REG_Motion_Burst 0x50
+#define REG_SROM_Load_Burst 0x62
+#define REG_Lift_Config 0x63
+#define REG_RawData_Burst 0x64
+#define REG_LiftCutoff_Cal2 0x65
+#define REG_LiftCutoff_Cal_Timeout 0x71
+#define REG_LiftCutoff_Cal_Min_Length 0x72
+#define REG_PWM_Period_Cnt 0x73
+#define REG_PWM_Width_Cnt 0x74
+
+#define CPI_STEP 50
+// clang-format on
+
+// limits to 0--319, resulting in a CPI range of 50 -- 16000 (as only steps of 50 are possible).
+#ifndef MAX_CPI
+# define MAX_CPI 0x013f
+#endif
+
+bool _inBurst = false;
+
+#ifdef CONSOLE_ENABLE
+void print_byte(uint8_t byte) {
+ dprintf("%c%c%c%c%c%c%c%c|", (byte & 0x80 ? '1' : '0'), (byte & 0x40 ? '1' : '0'), (byte & 0x20 ? '1' : '0'), (byte & 0x10 ? '1' : '0'), (byte & 0x08 ? '1' : '0'), (byte & 0x04 ? '1' : '0'), (byte & 0x02 ? '1' : '0'), (byte & 0x01 ? '1' : '0'));
+}
+#endif
+#define constrain(amt, low, high) ((amt) < (low) ? (low) : ((amt) > (high) ? (high) : (amt)))
+
+bool pmw3389_spi_start(void) {
+ bool status = spi_start(PMW3389_CS_PIN, PMW3389_SPI_LSBFIRST, PMW3389_SPI_MODE, PMW3389_SPI_DIVISOR);
+ // tNCS-SCLK, 120ns
+ wait_us(1);
+ return status;
+}
+
+spi_status_t pmw3389_write(uint8_t reg_addr, uint8_t data) {
+ pmw3389_spi_start();
+
+ if (reg_addr != REG_Motion_Burst) {
+ _inBurst = false;
+ }
+
+ // send address of the register, with MSBit = 1 to indicate it's a write
+ spi_status_t status = spi_write(reg_addr | 0x80);
+ status = spi_write(data);
+
+ // tSCLK-NCS for write operation is 35 us
+ wait_us(35);
+ spi_stop();
+
+ // tSWW/tSWR (=180us) minus tSCLK-NCS. Could be shortened, but is looks like a safe lower bound
+ wait_us(145);
+ return status;
+}
+
+uint8_t pmw3389_read(uint8_t reg_addr) {
+ pmw3389_spi_start();
+ // send adress of the register, with MSBit = 0 to indicate it's a read
+ spi_write(reg_addr & 0x7f);
+ // tSRAD (=160us)
+ wait_us(160);
+ uint8_t data = spi_read();
+
+ // tSCLK-NCS, 120ns
+ wait_us(1);
+ spi_stop();
+
+ // tSRW/tSRR (=20us) minus tSCLK-NCS
+ wait_us(19);
+ return data;
+}
+
+bool pmw3389_init(void) {
+ setPinOutput(PMW3389_CS_PIN);
+
+ spi_init();
+ _inBurst = false;
+
+ spi_stop();
+ pmw3389_spi_start();
+ spi_stop();
+
+ pmw3389_write(REG_Shutdown, 0xb6); // Shutdown first
+ wait_ms(300);
+
+ pmw3389_spi_start();
+ wait_us(40);
+ spi_stop();
+ wait_us(40);
+
+ // power up, need to first drive NCS high then low, see above.
+ pmw3389_write(REG_Power_Up_Reset, 0x5a);
+ wait_ms(50);
+
+ // read registers and discard
+ pmw3389_read(REG_Motion);
+ pmw3389_read(REG_Delta_X_L);
+ pmw3389_read(REG_Delta_X_H);
+ pmw3389_read(REG_Delta_Y_L);
+ pmw3389_read(REG_Delta_Y_H);
+
+ pmw3389_upload_firmware();
+
+ spi_stop();
+
+ wait_ms(10);
+ pmw3389_set_cpi(PMW3389_CPI);
+
+ wait_ms(1);
+
+ pmw3389_write(REG_Config2, 0x00);
+
+ pmw3389_write(REG_Angle_Tune, constrain(ROTATIONAL_TRANSFORM_ANGLE, -127, 127));
+
+ pmw3389_write(REG_Lift_Config, PMW3389_LIFTOFF_DISTANCE);
+
+ bool init_success = pmw3389_check_signature();
+#ifdef CONSOLE_ENABLE
+ if (init_success) {
+ dprintf("pmw3389 signature verified");
+ } else {
+ dprintf("pmw3389 signature verification failed!");
+ }
+#endif
+
+ writePinLow(PMW3389_CS_PIN);
+
+ return init_success;
+}
+
+void pmw3389_upload_firmware(void) {
+ // Datasheet claims we need to disable REST mode first, but during startup
+ // it's already disabled and we're not turning it on ...
+ // pmw3389_write(REG_Config2, 0x00); // disable REST mode
+ pmw3389_write(REG_SROM_Enable, 0x1d);
+
+ wait_ms(10);
+
+ pmw3389_write(REG_SROM_Enable, 0x18);
+
+ pmw3389_spi_start();
+ spi_write(REG_SROM_Load_Burst | 0x80);
+ wait_us(15);
+
+ for (uint16_t i = 0; i < FIRMWARE_LENGTH; i++) {
+ spi_write(pgm_read_byte(firmware_data + i));
+#ifndef PMW3389_FIRMWARE_UPLOAD_FAST
+ wait_us(15);
+#endif
+ }
+ wait_us(200);
+
+ pmw3389_read(REG_SROM_ID);
+ pmw3389_write(REG_Config2, 0x00);
+}
+
+bool pmw3389_check_signature(void) {
+ uint8_t pid = pmw3389_read(REG_Product_ID);
+ uint8_t iv_pid = pmw3389_read(REG_Inverse_Product_ID);
+ uint8_t SROM_ver = pmw3389_read(REG_SROM_ID);
+ return (pid == firmware_signature[0] && iv_pid == firmware_signature[1] && SROM_ver == firmware_signature[2]); // signature for SROM 0x04
+}
+
+uint16_t pmw3389_get_cpi(void) {
+ uint16_t cpival = (pmw3389_read(REG_Resolution_H) << 8) | pmw3389_read(REG_Resolution_L);
+ return (uint16_t)((cpival + 1) & 0xffff) * CPI_STEP;
+}
+
+void pmw3389_set_cpi(uint16_t cpi) {
+ uint16_t cpival = constrain((cpi / CPI_STEP) - 1, 0, MAX_CPI);
+ // Sets upper byte first for more consistent setting of cpi
+ pmw3389_write(REG_Resolution_H, (cpival >> 8) & 0xff);
+ pmw3389_write(REG_Resolution_L, cpival & 0xff);
+}
+
+report_pmw3389_t pmw3389_read_burst(void) {
+ report_pmw3389_t report = {0};
+
+ if (!_inBurst) {
+#ifdef CONSOLE_ENABLE
+ dprintf("burst on");
+#endif
+ pmw3389_write(REG_Motion_Burst, 0x00);
+ _inBurst = true;
+ }
+
+ pmw3389_spi_start();
+ spi_write(REG_Motion_Burst);
+ wait_us(35); // waits for tSRAD_MOTBR
+
+ report.motion = spi_read();
+ spi_read(); // skip Observation
+ // delta registers
+ report.dx = spi_read();
+ report.mdx = spi_read();
+ report.dy = spi_read();
+ report.mdy = spi_read();
+
+ if (report.motion & 0b111) { // panic recovery, sometimes burst mode works weird.
+ _inBurst = false;
+ }
+
+ spi_stop();
+
+#ifdef CONSOLE_ENABLE
+ if (debug_mouse) {
+ print_byte(report.motion);
+ print_byte(report.dx);
+ print_byte(report.mdx);
+ print_byte(report.dy);
+ print_byte(report.mdy);
+ dprintf("\n");
+ }
+#endif
+
+ report.isMotion = (report.motion & 0x80) != 0;
+ report.isOnSurface = (report.motion & 0x08) == 0;
+ report.dx |= (report.mdx << 8);
+ report.dx = report.dx * -1;
+ report.dy |= (report.mdy << 8);
+ report.dy = report.dy * -1;
+
+ return report;
+}
diff --git a/drivers/sensors/pmw3389.h b/drivers/sensors/pmw3389.h
new file mode 100644
index 0000000000..db4a763fe3
--- /dev/null
+++ b/drivers/sensors/pmw3389.h
@@ -0,0 +1,76 @@
+/* Copyright 2021 Alabastard (@Alabastard-64)
+ * Copyright 2020 Christopher Courtney, aka Drashna Jael're (@drashna) <drashna@live.com>
+ * Copyright 2019 Sunjun Kim
+ * Copyright 2020 Ploopy Corporation
+ *
+ * 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 2 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/>.
+ */
+
+#pragma once
+
+#include <stdint.h>
+
+#ifndef PMW3389_CPI
+# define PMW3389_CPI 2000
+#endif
+
+#ifndef PMW3389_CLOCK_SPEED
+# define PMW3389_CLOCK_SPEED 2000000
+#endif
+
+#ifndef PMW3389_SPI_LSBFIRST
+# define PMW3389_SPI_LSBFIRST false
+#endif
+
+#ifndef PMW3389_SPI_MODE
+# define PMW3389_SPI_MODE 3
+#endif
+
+#ifndef PMW3389_SPI_DIVISOR
+# ifdef __AVR__
+# define PMW3389_SPI_DIVISOR (F_CPU / PMW3389_CLOCK_SPEED)
+# else
+# define PMW3389_SPI_DIVISOR 64
+# endif
+#endif
+
+#ifndef PMW3389_LIFTOFF_DISTANCE
+# define PMW3389_LIFTOFF_DISTANCE 0x02
+#endif
+
+#ifndef ROTATIONAL_TRANSFORM_ANGLE
+# define ROTATIONAL_TRANSFORM_ANGLE 0x00
+#endif
+
+#ifndef PMW3389_CS_PIN
+# error "No chip select pin defined -- missing PMW3389_CS_PIN"
+#endif
+
+typedef struct {
+ int8_t motion;
+ bool isMotion; // True if a motion is detected.
+ bool isOnSurface; // True when a chip is on a surface
+ int16_t dx; // displacement on x directions. Unit: Count. (CPI * Count = Inch value)
+ int8_t mdx;
+ int16_t dy; // displacement on y directions.
+ int8_t mdy;
+} report_pmw3389_t;
+
+bool pmw3389_init(void);
+void pmw3389_upload_firmware(void);
+bool pmw3389_check_signature(void);
+uint16_t pmw3389_get_cpi(void);
+void pmw3389_set_cpi(uint16_t cpi);
+/* Reads and clears the current delta values on the sensor */
+report_pmw3389_t pmw3389_read_burst(void);
diff --git a/drivers/sensors/pmw3389_firmware.h b/drivers/sensors/pmw3389_firmware.h
index 0564dab73a..cd9638b605 100644
--- a/drivers/sensors/pmw3389_firmware.h
+++ b/drivers/sensors/pmw3389_firmware.h
@@ -18,286 +18,290 @@
#pragma once
+#include "progmem.h"
+
// PID, Inverse PID, SROM version
const uint8_t firmware_signature[] PROGMEM = {0x42, 0xBD, 0x04};
+#define FIRMWARE_LENGTH 4094
+
+// Firmware Blob for PMW3389
+
// clang-format off
-// Firmware Blob foor PMW3389
-const uint16_t firmware_length = 4094;
-// clang-format off
-const uint8_t firmware_data[] PROGMEM = { // SROM 0x04
-0x01, 0xe8, 0xba, 0x26, 0x0b, 0xb2, 0xbe, 0xfe, 0x7e, 0x5f, 0x3c, 0xdb, 0x15, 0xa8, 0xb3,
-0xe4, 0x2b, 0xb5, 0xe8, 0x53, 0x07, 0x6d, 0x3b, 0xd1, 0x20, 0xc2, 0x06, 0x6f, 0x3d, 0xd9,
-0x11, 0xa0, 0xc2, 0xe7, 0x2d, 0xb9, 0xd1, 0x20, 0xa3, 0xa5, 0xc8, 0xf3, 0x64, 0x4a, 0xf7,
-0x4d, 0x18, 0x93, 0xa4, 0xca, 0xf7, 0x6c, 0x5a, 0x36, 0xee, 0x5e, 0x3e, 0xfe, 0x7e, 0x7e,
-0x5f, 0x1d, 0x99, 0xb0, 0xc3, 0xe5, 0x29, 0xd3, 0x03, 0x65, 0x48, 0x12, 0x87, 0x6d, 0x58,
-0x32, 0xe6, 0x2f, 0xdc, 0x3a, 0xf2, 0x4f, 0xfd, 0x59, 0x11, 0x81, 0x61, 0x21, 0xc0, 0x02,
-0x86, 0x8e, 0x7f, 0x5d, 0x38, 0xf2, 0x47, 0x0c, 0x7b, 0x55, 0x28, 0xb3, 0xe4, 0x4a, 0x16,
-0xab, 0xbf, 0xdd, 0x38, 0xf2, 0x66, 0x4e, 0xff, 0x5d, 0x19, 0x91, 0xa0, 0xa3, 0xa5, 0xc8,
-0x12, 0xa6, 0xaf, 0xdc, 0x3a, 0xd1, 0x41, 0x60, 0x75, 0x58, 0x24, 0x92, 0xd4, 0x72, 0x6c,
-0xe0, 0x2f, 0xfd, 0x23, 0x8d, 0x1c, 0x5b, 0xb2, 0x97, 0x36, 0x3d, 0x0b, 0xa2, 0x49, 0xb1,
-0x58, 0xf2, 0x1f, 0xc0, 0xcb, 0xf8, 0x41, 0x4f, 0xcd, 0x1e, 0x6b, 0x39, 0xa7, 0x2b, 0xe9,
-0x30, 0x16, 0x83, 0xd2, 0x0e, 0x47, 0x8f, 0xe3, 0xb1, 0xdf, 0xa2, 0x15, 0xdb, 0x5d, 0x30,
-0xc5, 0x1a, 0xab, 0x31, 0x99, 0xf3, 0xfa, 0xb2, 0x86, 0x69, 0xad, 0x7a, 0xe8, 0xa7, 0x18,
-0x6a, 0xcc, 0xc8, 0x65, 0x23, 0x87, 0xa8, 0x5f, 0xf5, 0x21, 0x59, 0x75, 0x09, 0x71, 0x45,
-0x55, 0x25, 0x4b, 0xda, 0xa1, 0xc3, 0xf7, 0x41, 0xab, 0x59, 0xd9, 0x74, 0x12, 0x55, 0x5f,
-0xbc, 0xaf, 0xd9, 0xfd, 0xb0, 0x1e, 0xa3, 0x0f, 0xff, 0xde, 0x11, 0x16, 0x6a, 0xae, 0x0e,
-0xe1, 0x5d, 0x3c, 0x10, 0x43, 0x9a, 0xa1, 0x0b, 0x24, 0x8f, 0x0d, 0x7f, 0x0b, 0x5e, 0x4c,
-0x42, 0xa4, 0x84, 0x2c, 0x40, 0xd0, 0x55, 0x39, 0xe6, 0x4b, 0xf8, 0x9b, 0x2f, 0xdc, 0x28,
-0xff, 0xfa, 0xb5, 0x85, 0x19, 0xe5, 0x28, 0xa1, 0x77, 0xaa, 0x73, 0xf3, 0x03, 0xc7, 0x62,
-0xa6, 0x91, 0x18, 0xc9, 0xb0, 0xcd, 0x05, 0xdc, 0xca, 0x81, 0x26, 0x1a, 0x47, 0x40, 0xda,
-0x36, 0x7d, 0x6a, 0x53, 0xc8, 0x5a, 0x77, 0x5d, 0x19, 0xa4, 0x1b, 0x23, 0x83, 0xd0, 0xb2,
-0xaa, 0x0e, 0xbf, 0x77, 0x4e, 0x3a, 0x3b, 0x59, 0x00, 0x31, 0x0d, 0x02, 0x1b, 0x88, 0x7a,
-0xd4, 0xbd, 0x9d, 0xcc, 0x58, 0x04, 0x69, 0xf6, 0x3b, 0xca, 0x42, 0xe2, 0xfd, 0xc3, 0x3d,
-0x39, 0xc5, 0xd0, 0x71, 0xe4, 0xc8, 0xb7, 0x3e, 0x3f, 0xc8, 0xe9, 0xca, 0xc9, 0x3f, 0x04,
-0x4e, 0x1b, 0x79, 0xca, 0xa5, 0x61, 0xc2, 0xed, 0x1d, 0xa6, 0xda, 0x5a, 0xe9, 0x7f, 0x65,
-0x8c, 0xbe, 0x12, 0x6e, 0xa4, 0x5b, 0x33, 0x2f, 0x84, 0x28, 0x9c, 0x1c, 0x88, 0x2d, 0xff,
-0x07, 0xbf, 0xa6, 0xd7, 0x5a, 0x88, 0x86, 0xb0, 0x3f, 0xf6, 0x31, 0x5b, 0x11, 0x6d, 0xf5,
-0x58, 0xeb, 0x58, 0x02, 0x9e, 0xb5, 0x9a, 0xb1, 0xff, 0x25, 0x9d, 0x8b, 0x4f, 0xb6, 0x0a,
-0xf9, 0xea, 0x3e, 0x3f, 0x21, 0x09, 0x65, 0x21, 0x22, 0xfe, 0x3d, 0x4e, 0x11, 0x5b, 0x9e,
-0x5a, 0x59, 0x8b, 0xdd, 0xd8, 0xce, 0xd6, 0xd9, 0x59, 0xd2, 0x1e, 0xfd, 0xef, 0x0d, 0x1b,
-0xd9, 0x61, 0x7f, 0xd7, 0x2d, 0xad, 0x62, 0x09, 0xe5, 0x22, 0x63, 0xea, 0xc7, 0x31, 0xd9,
-0xa1, 0x38, 0x80, 0x5c, 0xa7, 0x32, 0x82, 0xec, 0x1b, 0xa2, 0x49, 0x5a, 0x06, 0xd2, 0x7c,
-0xc9, 0x96, 0x57, 0xbb, 0x17, 0x75, 0xfc, 0x7a, 0x8f, 0x0d, 0x77, 0xb5, 0x7a, 0x8e, 0x3e,
-0xf4, 0xba, 0x2f, 0x69, 0x13, 0x26, 0xd6, 0xd9, 0x21, 0x60, 0x2f, 0x21, 0x3e, 0x87, 0xee,
-0xfd, 0x87, 0x16, 0x0d, 0xc8, 0x08, 0x00, 0x25, 0x71, 0xac, 0x2c, 0x03, 0x2a, 0x37, 0x2d,
-0xb3, 0x34, 0x09, 0x91, 0xe3, 0x06, 0x2c, 0x38, 0x37, 0x95, 0x3b, 0x17, 0x7a, 0xaf, 0xac,
-0x99, 0x55, 0xab, 0x41, 0x39, 0x5f, 0x8e, 0xa6, 0x43, 0x80, 0x03, 0x88, 0x6f, 0x7d, 0xbd,
-0x5a, 0xb4, 0x2b, 0x32, 0x23, 0x5a, 0xa9, 0x31, 0x32, 0x39, 0x4c, 0x5b, 0xf4, 0x6b, 0xaf,
-0x66, 0x6f, 0x3c, 0x8e, 0x2d, 0x82, 0x97, 0x9f, 0x4a, 0x01, 0xdc, 0x99, 0x98, 0x00, 0xec,
-0x38, 0x7a, 0x79, 0x70, 0xa6, 0x85, 0xd6, 0x21, 0x63, 0x0d, 0x45, 0x9a, 0x2e, 0x5e, 0xa7,
-0xb1, 0xea, 0x66, 0x6a, 0xbc, 0x62, 0x2d, 0x7b, 0x7d, 0x85, 0xea, 0x95, 0x2f, 0xc0, 0xe8,
-0x6f, 0x35, 0xa0, 0x3a, 0x02, 0x25, 0xbc, 0xb2, 0x5f, 0x5c, 0x43, 0x96, 0xcc, 0x26, 0xd2,
-0x16, 0xb4, 0x96, 0x73, 0xd7, 0x13, 0xc7, 0xae, 0x53, 0x15, 0x31, 0x89, 0x68, 0x66, 0x6d,
-0x2c, 0x92, 0x1f, 0xcc, 0x5b, 0xa7, 0x8f, 0x5d, 0xbb, 0xc9, 0xdb, 0xe8, 0x3b, 0x9d, 0x61,
-0x74, 0x8b, 0x05, 0xa1, 0x58, 0x52, 0x68, 0xee, 0x3d, 0x39, 0x79, 0xa0, 0x9b, 0xdd, 0xe1,
-0x55, 0xc9, 0x60, 0xeb, 0xad, 0xb8, 0x5b, 0xc2, 0x5a, 0xb5, 0x2c, 0x18, 0x55, 0xa9, 0x50,
-0xc3, 0xf6, 0x72, 0x5f, 0xcc, 0xe2, 0xf4, 0x55, 0xb5, 0xd6, 0xb5, 0x4a, 0x99, 0xa5, 0x28,
-0x74, 0x97, 0x18, 0xe8, 0xc0, 0x84, 0x89, 0x50, 0x03, 0x86, 0x4d, 0x1a, 0xb7, 0x09, 0x90,
-0xa2, 0x01, 0x04, 0xbb, 0x73, 0x62, 0xcb, 0x97, 0x22, 0x70, 0x5d, 0x52, 0x41, 0x8e, 0xd9,
-0x90, 0x15, 0xaa, 0xab, 0x0a, 0x31, 0x65, 0xb4, 0xda, 0xd0, 0xee, 0x24, 0xc9, 0x41, 0x91,
-0x1e, 0xbc, 0x46, 0x70, 0x40, 0x9d, 0xda, 0x0e, 0x2a, 0xe4, 0xb2, 0x4c, 0x9f, 0xf2, 0xfc,
-0xf3, 0x84, 0x17, 0x44, 0x1e, 0xd7, 0xca, 0x23, 0x1f, 0x3f, 0x5a, 0x22, 0x3d, 0xaf, 0x9b,
-0x2d, 0xfc, 0x41, 0xad, 0x26, 0xb4, 0x45, 0x67, 0x0b, 0x80, 0x0e, 0xf9, 0x61, 0x37, 0xec,
-0x3b, 0xf4, 0x4b, 0x14, 0xdf, 0x5a, 0x0c, 0x3a, 0x50, 0x0b, 0x14, 0x0c, 0x72, 0xae, 0xc6,
-0xc5, 0xec, 0x35, 0x53, 0x2d, 0x59, 0xed, 0x91, 0x74, 0xe2, 0xc4, 0xc8, 0xf2, 0x25, 0x6b,
-0x97, 0x6f, 0xc9, 0x76, 0xce, 0xa9, 0xb1, 0x99, 0x8f, 0x5a, 0x92, 0x3b, 0xc4, 0x8d, 0x54,
-0x50, 0x40, 0x72, 0xd6, 0x90, 0x83, 0xfc, 0xe5, 0x49, 0x8b, 0x17, 0xf5, 0xfd, 0x6b, 0x8d,
-0x32, 0x02, 0xe9, 0x0a, 0xfe, 0xbf, 0x00, 0x6b, 0xa3, 0xad, 0x5f, 0x09, 0x4b, 0x97, 0x2b,
-0x00, 0x58, 0x65, 0x2e, 0x07, 0x49, 0x0a, 0x3b, 0x6b, 0x2e, 0x50, 0x6c, 0x1d, 0xac, 0xb7,
-0x6a, 0x26, 0xd8, 0x13, 0xa4, 0xca, 0x16, 0xae, 0xab, 0x93, 0xb9, 0x1c, 0x1c, 0xb4, 0x47,
-0x6a, 0x38, 0x36, 0x17, 0x27, 0xc9, 0x7f, 0xc7, 0x64, 0xcb, 0x89, 0x58, 0xc5, 0x61, 0xc2,
-0xc6, 0xea, 0x15, 0x0b, 0x34, 0x0c, 0x5d, 0x61, 0x76, 0x6e, 0x2b, 0x62, 0x40, 0x92, 0xa3,
-0x6c, 0xef, 0xf4, 0xe4, 0xc3, 0xa1, 0xa8, 0xf5, 0x94, 0x79, 0x0d, 0xd1, 0x3d, 0xcb, 0x3d,
-0x40, 0xb6, 0xd0, 0xf0, 0x10, 0x54, 0xd8, 0x47, 0x25, 0x51, 0xc5, 0x41, 0x79, 0x00, 0xe5,
-0xa0, 0x72, 0xde, 0xbb, 0x3b, 0x62, 0x17, 0xf6, 0xbc, 0x5d, 0x00, 0x76, 0x2e, 0xa7, 0x3b,
-0xb6, 0xf1, 0x98, 0x72, 0x59, 0x2a, 0x73, 0xb0, 0x21, 0xd6, 0x49, 0xe0, 0xc0, 0xd5, 0xeb,
-0x02, 0x7d, 0x4b, 0x41, 0x28, 0x70, 0x2d, 0xec, 0x2b, 0x71, 0x1f, 0x0b, 0xb9, 0x71, 0x63,
-0x06, 0xe6, 0xbc, 0x60, 0xbb, 0xf4, 0x9a, 0x62, 0x43, 0x09, 0x18, 0x4e, 0x93, 0x06, 0x4d,
-0x76, 0xfa, 0x7f, 0xbd, 0x02, 0xe4, 0x50, 0x91, 0x12, 0xe5, 0x86, 0xff, 0x64, 0x1e, 0xaf,
-0x7e, 0xb3, 0xb2, 0xde, 0x89, 0xc1, 0xa2, 0x6f, 0x40, 0x7b, 0x41, 0x51, 0x63, 0xea, 0x25,
-0xd1, 0x97, 0x57, 0x92, 0xa8, 0x45, 0xa1, 0xa5, 0x45, 0x21, 0x43, 0x7f, 0x83, 0x15, 0x29,
-0xd0, 0x30, 0x53, 0x32, 0xb4, 0x5a, 0x17, 0x96, 0xbc, 0xc2, 0x68, 0xa9, 0xb7, 0xaf, 0xac,
-0xdf, 0xf1, 0xe3, 0x89, 0xba, 0x24, 0x79, 0x54, 0xc6, 0x14, 0x07, 0x1c, 0x1e, 0x0d, 0x3a,
-0x6b, 0xe5, 0x3d, 0x4e, 0x10, 0x60, 0x96, 0xec, 0x6c, 0xda, 0x47, 0xae, 0x03, 0x25, 0x39,
-0x1d, 0x74, 0xc8, 0xac, 0x6a, 0xf2, 0x6b, 0x05, 0x2a, 0x9a, 0xe7, 0xe8, 0x92, 0xd6, 0xc2,
-0x6d, 0xfa, 0xe8, 0xa7, 0x9d, 0x5f, 0x48, 0xc9, 0x75, 0xf1, 0x66, 0x6a, 0xdb, 0x5d, 0x9a,
-0xcd, 0x27, 0xdd, 0xb9, 0x24, 0x04, 0x9c, 0x18, 0xc2, 0x6d, 0x0c, 0x91, 0x34, 0x48, 0x42,
-0x6f, 0xe9, 0x59, 0x70, 0xc4, 0x7e, 0x81, 0x0e, 0x32, 0x0a, 0x93, 0x48, 0xb0, 0xc0, 0x15,
-0x9e, 0x05, 0xac, 0x36, 0x16, 0xcb, 0x59, 0x65, 0xa0, 0x83, 0xdf, 0x3e, 0xda, 0xfb, 0x1d,
-0x1a, 0xdb, 0x65, 0xec, 0x9a, 0xc6, 0xc3, 0x8e, 0x3c, 0x45, 0xfd, 0xc8, 0xf5, 0x1c, 0x6a,
-0x67, 0x0d, 0x8f, 0x99, 0x7d, 0x30, 0x21, 0x8c, 0xea, 0x22, 0x87, 0x65, 0xc9, 0xb2, 0x4c,
-0xe4, 0x1b, 0x46, 0xba, 0x54, 0xbd, 0x7c, 0xca, 0xd5, 0x8f, 0x5b, 0xa5, 0x01, 0x04, 0xd8,
-0x0a, 0x16, 0xbf, 0xb9, 0x50, 0x2e, 0x37, 0x2f, 0x64, 0xf3, 0x70, 0x11, 0x02, 0x05, 0x31,
-0x9b, 0xa0, 0xb2, 0x01, 0x5e, 0x4f, 0x19, 0xc9, 0xd4, 0xea, 0xa1, 0x79, 0x54, 0x53, 0xa7,
-0xde, 0x2f, 0x49, 0xd3, 0xd1, 0x63, 0xb5, 0x03, 0x15, 0x4e, 0xbf, 0x04, 0xb3, 0x26, 0x8b,
-0x20, 0xb2, 0x45, 0xcf, 0xcd, 0x5b, 0x82, 0x32, 0x88, 0x61, 0xa7, 0xa8, 0xb2, 0xa0, 0x72,
-0x96, 0xc0, 0xdb, 0x2b, 0xe2, 0x5f, 0xba, 0xe3, 0xf5, 0x8a, 0xde, 0xf1, 0x18, 0x01, 0x16,
-0x40, 0xd9, 0x86, 0x12, 0x09, 0x18, 0x1b, 0x05, 0x0c, 0xb1, 0xb5, 0x47, 0xe2, 0x43, 0xab,
-0xfe, 0x92, 0x63, 0x7e, 0x95, 0x2b, 0xf0, 0xaf, 0xe1, 0xf1, 0xc3, 0x4a, 0xff, 0x2b, 0x09,
-0xbb, 0x4a, 0x0e, 0x9a, 0xc4, 0xd8, 0x64, 0x7d, 0x83, 0xa0, 0x4f, 0x44, 0xdb, 0xc4, 0xa8,
-0x58, 0xef, 0xfc, 0x9e, 0x77, 0xf9, 0xa6, 0x8f, 0x58, 0x8b, 0x12, 0xf4, 0xe9, 0x81, 0x12,
-0x47, 0x51, 0x41, 0x83, 0xef, 0xf6, 0x73, 0xbc, 0x8e, 0x0f, 0x4c, 0x8f, 0x4e, 0x69, 0x90,
-0x77, 0x29, 0x5d, 0x92, 0xb0, 0x6d, 0x06, 0x67, 0x29, 0x60, 0xbd, 0x4b, 0x17, 0xc8, 0x89,
-0x69, 0x28, 0x29, 0xd6, 0x78, 0xcb, 0x11, 0x4c, 0xba, 0x8b, 0x68, 0xae, 0x7e, 0x9f, 0xef,
-0x95, 0xda, 0xe2, 0x9e, 0x7f, 0xe9, 0x55, 0xe5, 0xe1, 0xe2, 0xb7, 0xe6, 0x5f, 0xbb, 0x2c,
-0xa2, 0xe6, 0xee, 0xc7, 0x0a, 0x60, 0xa9, 0xd1, 0x80, 0xdf, 0x7f, 0xd6, 0x97, 0xab, 0x1d,
-0x22, 0x25, 0xfc, 0x79, 0x23, 0xe0, 0xae, 0xc5, 0xef, 0x16, 0xa4, 0xa1, 0x0f, 0x92, 0xa9,
-0xc7, 0xe3, 0x3a, 0x55, 0xdf, 0x62, 0x49, 0xd9, 0xf5, 0x84, 0x49, 0xc5, 0x90, 0x34, 0xd3,
-0xe1, 0xac, 0x99, 0x21, 0xb1, 0x02, 0x76, 0x4a, 0xfa, 0xd4, 0xbb, 0xa4, 0x9c, 0xa2, 0xe2,
-0xcb, 0x3d, 0x3b, 0x14, 0x75, 0x60, 0xd1, 0x02, 0xb4, 0xa3, 0xb4, 0x72, 0x06, 0xf9, 0x19,
-0x9c, 0xe2, 0xe4, 0xa7, 0x0f, 0x25, 0x88, 0xc6, 0x86, 0xd6, 0x8c, 0x74, 0x4e, 0x6e, 0xfc,
-0xa8, 0x48, 0x9e, 0xa7, 0x9d, 0x1a, 0x4b, 0x37, 0x09, 0xc8, 0xb0, 0x10, 0xbe, 0x6f, 0xfe,
-0xa3, 0xc4, 0x7a, 0xb5, 0x3d, 0xe8, 0x30, 0xf1, 0x0d, 0xa0, 0xb2, 0x44, 0xfc, 0x9b, 0x8c,
-0xf8, 0x61, 0xed, 0x81, 0xd1, 0x62, 0x11, 0xb4, 0xe1, 0xd5, 0x39, 0x52, 0x89, 0xd3, 0xa8,
-0x49, 0x31, 0xdf, 0xb6, 0xf9, 0x91, 0xf4, 0x1c, 0x9d, 0x09, 0x95, 0x40, 0x56, 0xe7, 0xe3,
-0xcd, 0x5c, 0x92, 0xc1, 0x1d, 0x6b, 0xe9, 0x78, 0x6f, 0x8e, 0x94, 0x42, 0x66, 0xa2, 0xaa,
-0xd3, 0xc8, 0x2e, 0xe3, 0xf6, 0x07, 0x72, 0x0b, 0x6b, 0x1e, 0x7b, 0xb9, 0x7c, 0xe0, 0xa0,
-0xbc, 0xd9, 0x25, 0xdf, 0x87, 0xa8, 0x5f, 0x9c, 0xcc, 0xf0, 0xdb, 0x42, 0x8e, 0x07, 0x31,
-0x13, 0x01, 0x66, 0x32, 0xd1, 0xb8, 0xd6, 0xe3, 0x5e, 0x12, 0x76, 0x61, 0xd3, 0x38, 0x89,
-0xe6, 0x17, 0x6f, 0xa5, 0xf2, 0x71, 0x0e, 0xa5, 0xe2, 0x88, 0x30, 0xbb, 0xbe, 0x8a, 0xea,
-0xc7, 0x62, 0xc4, 0xcf, 0xb8, 0xcd, 0x33, 0x8d, 0x3d, 0x3e, 0xb5, 0x60, 0x3a, 0x03, 0x92,
-0xe4, 0x6d, 0x1b, 0xe0, 0xb4, 0x84, 0x08, 0x55, 0x88, 0xa7, 0x3a, 0xb9, 0x3d, 0x43, 0xc3,
-0xc0, 0xfa, 0x07, 0x6a, 0xca, 0x94, 0xad, 0x99, 0x55, 0xf1, 0xf1, 0xc0, 0x23, 0x87, 0x1d,
-0x3d, 0x1c, 0xd1, 0x66, 0xa0, 0x57, 0x10, 0x52, 0xa2, 0x7f, 0xbe, 0xf9, 0x88, 0xb6, 0x02,
-0xbf, 0x08, 0x23, 0xa9, 0x0c, 0x63, 0x17, 0x2a, 0xae, 0xf5, 0xf7, 0xb7, 0x21, 0x83, 0x92,
-0x31, 0x23, 0x0d, 0x20, 0xc3, 0xc2, 0x05, 0x21, 0x62, 0x8e, 0x45, 0xe8, 0x14, 0xc1, 0xda,
-0x75, 0xb8, 0xf8, 0x92, 0x01, 0xd0, 0x5d, 0x18, 0x9f, 0x99, 0x11, 0x19, 0xf5, 0x35, 0xe8,
-0x7f, 0x20, 0x88, 0x8c, 0x05, 0x75, 0xf5, 0xd7, 0x40, 0x17, 0xbb, 0x1e, 0x36, 0x52, 0xd9,
-0xa4, 0x9c, 0xc2, 0x9d, 0x42, 0x81, 0xd8, 0xc7, 0x8a, 0xe7, 0x4c, 0x81, 0xe0, 0xb7, 0x57,
-0xed, 0x48, 0x8b, 0xf0, 0x97, 0x15, 0x61, 0xd9, 0x2c, 0x7c, 0x45, 0xaf, 0xc2, 0xcd, 0xfc,
-0xaa, 0x13, 0xad, 0x59, 0xcc, 0xb2, 0xb2, 0x6e, 0xdd, 0x63, 0x9c, 0x32, 0x0f, 0xec, 0x83,
-0xbe, 0x78, 0xac, 0x91, 0x44, 0x1a, 0x1f, 0xea, 0xfd, 0x5d, 0x8e, 0xb4, 0xc0, 0x84, 0xd4,
-0xac, 0xb4, 0x87, 0x5f, 0xac, 0xef, 0xdf, 0xcd, 0x12, 0x56, 0xc8, 0xcd, 0xfe, 0xc5, 0xda,
-0xd3, 0xc1, 0x69, 0xf3, 0x61, 0x05, 0xea, 0x25, 0xe2, 0x12, 0x05, 0x8f, 0x39, 0x08, 0x08,
-0x7c, 0x37, 0xb6, 0x7e, 0x5b, 0xd8, 0xb1, 0x0e, 0xf2, 0xdb, 0x4b, 0xf1, 0xad, 0x90, 0x01,
-0x57, 0xcd, 0xa0, 0xb4, 0x52, 0xe8, 0xf3, 0xd7, 0x8a, 0xbd, 0x4f, 0x9f, 0x21, 0x40, 0x72,
-0xa4, 0xfc, 0x0b, 0x01, 0x2b, 0x2f, 0xb6, 0x4c, 0x95, 0x2d, 0x35, 0x33, 0x41, 0x6b, 0xa0,
-0x93, 0xe7, 0x2c, 0xf2, 0xd3, 0x72, 0x8b, 0xf4, 0x4f, 0x15, 0x3c, 0xaf, 0xd6, 0x12, 0xde,
-0x3f, 0x83, 0x3f, 0xff, 0xf8, 0x7f, 0xf6, 0xcc, 0xa6, 0x7f, 0xc9, 0x9a, 0x6e, 0x1f, 0xc1,
-0x0c, 0xfb, 0xee, 0x9c, 0xe7, 0xaf, 0xc9, 0x26, 0x54, 0xef, 0xb0, 0x39, 0xef, 0xb2, 0xe9,
-0x23, 0xc4, 0xef, 0xd1, 0xa1, 0xa4, 0x25, 0x24, 0x6f, 0x8d, 0x6a, 0xe5, 0x8a, 0x32, 0x3a,
-0xaf, 0xfc, 0xda, 0xce, 0x18, 0x25, 0x42, 0x07, 0x4d, 0x45, 0x8b, 0xdf, 0x85, 0xcf, 0x55,
-0xb2, 0x24, 0xfe, 0x9c, 0x69, 0x74, 0xa7, 0x6e, 0xa0, 0xce, 0xc0, 0x39, 0xf4, 0x86, 0xc6,
-0x8d, 0xae, 0xb9, 0x48, 0x64, 0x13, 0x0b, 0x40, 0x81, 0xa2, 0xc9, 0xa8, 0x85, 0x51, 0xee,
-0x9f, 0xcf, 0xa2, 0x8c, 0x19, 0x52, 0x48, 0xe2, 0xc1, 0xa8, 0x58, 0xb4, 0x10, 0x24, 0x06,
-0x58, 0x51, 0xfc, 0xb9, 0x12, 0xec, 0xfd, 0x73, 0xb4, 0x6d, 0x84, 0xfa, 0x06, 0x8b, 0x05,
-0x0b, 0x2d, 0xd6, 0xd6, 0x1f, 0x29, 0x82, 0x9f, 0x19, 0x12, 0x1e, 0xb2, 0x04, 0x8f, 0x7f,
-0x4d, 0xbd, 0x30, 0x2e, 0xe3, 0xe0, 0x88, 0x29, 0xc5, 0x93, 0xd6, 0x6c, 0x1f, 0x29, 0x45,
-0x91, 0xa7, 0x58, 0xcd, 0x05, 0x17, 0xd6, 0x6d, 0xb3, 0xca, 0x66, 0xcc, 0x3c, 0x4a, 0x74,
-0xfd, 0x08, 0x10, 0xa6, 0x99, 0x92, 0x10, 0xd2, 0x85, 0xab, 0x6e, 0x1d, 0x0e, 0x8b, 0x26,
-0x46, 0xd1, 0x6c, 0x84, 0xc0, 0x26, 0x43, 0x59, 0x68, 0xf0, 0x13, 0x1d, 0xfb, 0xe3, 0xd1,
-0xd2, 0xb4, 0x71, 0x9e, 0xf2, 0x59, 0x6a, 0x33, 0x29, 0x79, 0xd2, 0xd7, 0x26, 0xf1, 0xae,
-0x78, 0x9e, 0x1f, 0x0f, 0x3f, 0xe3, 0xe8, 0xd0, 0x27, 0x78, 0x77, 0xf6, 0xac, 0x9c, 0x56,
-0x39, 0x73, 0x8a, 0x6b, 0x2f, 0x34, 0x78, 0xb1, 0x11, 0xdb, 0xa4, 0x5c, 0x80, 0x01, 0x71,
-0x6a, 0xc2, 0xd1, 0x2e, 0x5e, 0x76, 0x28, 0x70, 0x93, 0xae, 0x3e, 0x78, 0xb0, 0x1f, 0x0f,
-0xda, 0xbf, 0xfb, 0x8a, 0x67, 0x65, 0x4f, 0x91, 0xed, 0x49, 0x75, 0x78, 0x62, 0xa2, 0x93,
-0xb5, 0x70, 0x7f, 0x4d, 0x08, 0x4e, 0x79, 0x61, 0xa8, 0x5f, 0x7f, 0xb4, 0x65, 0x9f, 0x91,
-0x54, 0x3a, 0xe8, 0x50, 0x33, 0xd3, 0xd5, 0x8a, 0x7c, 0xf3, 0x9e, 0x8b, 0x77, 0x7b, 0xc6,
-0xc6, 0x0c, 0x45, 0x95, 0x1f, 0xb0, 0xd0, 0x0b, 0x27, 0x4a, 0xfd, 0xc7, 0xf7, 0x0d, 0x5a,
-0x43, 0xc9, 0x7d, 0x35, 0xb0, 0x7d, 0xc4, 0x9c, 0x57, 0x1e, 0x76, 0x0d, 0xf1, 0x95, 0x30,
-0x71, 0xcc, 0xb3, 0x66, 0x3b, 0x63, 0xa8, 0x6c, 0xa3, 0x43, 0xa0, 0x24, 0xcc, 0xb7, 0x53,
-0xfe, 0xfe, 0xbc, 0x6e, 0x60, 0x89, 0xaf, 0x16, 0x21, 0xc8, 0x91, 0x6a, 0x89, 0xce, 0x80,
-0x2c, 0xf1, 0x59, 0xce, 0xc3, 0x60, 0x61, 0x3b, 0x0b, 0x19, 0xfe, 0x99, 0xac, 0x65, 0x90,
-0x15, 0x12, 0x05, 0xac, 0x7e, 0xff, 0x98, 0x7b, 0x66, 0x64, 0x0e, 0x4b, 0x5b, 0xaa, 0x8d,
-0x3b, 0xd2, 0x56, 0xcf, 0x99, 0x39, 0xee, 0x22, 0x81, 0xd0, 0x60, 0x06, 0x66, 0x20, 0x81,
-0x48, 0x3c, 0x6f, 0x3a, 0x77, 0xba, 0xcb, 0x52, 0xac, 0x79, 0x56, 0xaf, 0xe9, 0x16, 0x17,
-0x0a, 0xa3, 0x82, 0x08, 0xd5, 0x3c, 0x97, 0xcb, 0x09, 0xff, 0x7f, 0xf9, 0x4f, 0x60, 0x05,
-0xb9, 0x53, 0x26, 0xaa, 0xb8, 0x50, 0xaa, 0x19, 0x25, 0xae, 0x5f, 0xea, 0x8a, 0xd0, 0x89,
-0x12, 0x80, 0x43, 0x50, 0x24, 0x12, 0x21, 0x14, 0xcd, 0x77, 0xeb, 0x21, 0xcc, 0x5c, 0x09,
-0x64, 0xf3, 0xc7, 0xcb, 0xc5, 0x4b, 0xc3, 0xe7, 0xed, 0xe7, 0x86, 0x2c, 0x1d, 0x8e, 0x19,
-0x52, 0x9b, 0x2a, 0x0c, 0x18, 0x72, 0x0b, 0x1e, 0x1b, 0xb0, 0x0f, 0x42, 0x99, 0x04, 0xae,
-0xd5, 0xb7, 0x89, 0x1a, 0xb9, 0x4f, 0xd6, 0xaf, 0xf3, 0xc9, 0x93, 0x6f, 0xb0, 0x60, 0x83,
-0x6e, 0x6b, 0xd1, 0x5f, 0x3f, 0x1a, 0x83, 0x1e, 0x24, 0x00, 0x87, 0xb5, 0x3e, 0xdb, 0xf9,
-0x4d, 0xa7, 0x16, 0x2e, 0x19, 0x5b, 0x8f, 0x1b, 0x0d, 0x47, 0x72, 0x42, 0xe9, 0x0a, 0x11,
-0x08, 0x2d, 0x88, 0x1c, 0xbc, 0xc7, 0xb4, 0xbe, 0x29, 0x4d, 0x03, 0x5e, 0xec, 0xdf, 0xf3,
-0x3d, 0x2f, 0xe8, 0x1d, 0x9a, 0xd2, 0xd1, 0xab, 0x41, 0x3d, 0x87, 0x11, 0x45, 0xb0, 0x0d,
-0x46, 0xf5, 0xe8, 0x95, 0x62, 0x1c, 0x68, 0xf7, 0xa6, 0x5b, 0x39, 0x4e, 0xbf, 0x47, 0xba,
-0x5d, 0x7f, 0xb7, 0x6a, 0xf4, 0xba, 0x1d, 0x69, 0xf6, 0xa4, 0xe7, 0xe4, 0x6b, 0x3b, 0x0d,
-0x23, 0x16, 0x4a, 0xb2, 0x68, 0xf0, 0xb2, 0x0d, 0x09, 0x17, 0x6a, 0x63, 0x8c, 0x83, 0xd3,
-0xbd, 0x05, 0xc9, 0xf6, 0xf0, 0xa1, 0x31, 0x0b, 0x2c, 0xac, 0x83, 0xac, 0x80, 0x34, 0x32,
-0xb4, 0xec, 0xd0, 0xbc, 0x54, 0x82, 0x9a, 0xc8, 0xf6, 0xa0, 0x7d, 0xc6, 0x79, 0x73, 0xf4,
-0x20, 0x99, 0xf3, 0xb4, 0x01, 0xde, 0x91, 0x27, 0xf2, 0xc0, 0xdc, 0x81, 0x00, 0x4e, 0x7e,
-0x07, 0x99, 0xc8, 0x3a, 0x51, 0xbc, 0x38, 0xd6, 0x8a, 0xa2, 0xde, 0x3b, 0x6a, 0x8c, 0x1a,
-0x7c, 0x81, 0x0f, 0x3a, 0x1f, 0xe4, 0x05, 0x7b, 0x20, 0x35, 0x6b, 0xa5, 0x6a, 0xa7, 0xe7,
-0xbc, 0x9c, 0x20, 0xec, 0x00, 0x15, 0xe2, 0x51, 0xaf, 0x77, 0xeb, 0x29, 0x3c, 0x7d, 0x2e,
-0x00, 0x5c, 0x81, 0x21, 0xfa, 0x35, 0x6f, 0x40, 0xef, 0xfb, 0xd1, 0x3f, 0xcc, 0x9d, 0x55,
-0x53, 0xfb, 0x5a, 0xa5, 0x56, 0x89, 0x0b, 0x52, 0xeb, 0x57, 0x73, 0x4f, 0x1b, 0x67, 0x24,
-0xcb, 0xb8, 0x6a, 0x10, 0x69, 0xd6, 0xfb, 0x52, 0x40, 0xff, 0x20, 0xa5, 0xf3, 0x72, 0xe1,
-0x3d, 0xa4, 0x8c, 0x81, 0x66, 0x16, 0x0d, 0x5d, 0xad, 0xa8, 0x50, 0x25, 0x78, 0x31, 0x77,
-0x0c, 0x57, 0xe4, 0xe9, 0x15, 0x2d, 0xdb, 0x07, 0x87, 0xc8, 0xb0, 0x43, 0xde, 0xfc, 0xfe,
-0xa9, 0xeb, 0xf5, 0xb0, 0xd3, 0x7b, 0xe9, 0x1f, 0x6e, 0xca, 0xe4, 0x03, 0x95, 0xc5, 0xd1,
-0x59, 0x72, 0x63, 0xf0, 0x86, 0x54, 0xe8, 0x16, 0x62, 0x0b, 0x35, 0x29, 0xc2, 0x68, 0xd0,
-0xd6, 0x3e, 0x90, 0x60, 0x57, 0x1d, 0xc9, 0xed, 0x3f, 0xed, 0xb0, 0x2f, 0x7e, 0x97, 0x02,
-0x51, 0xec, 0xee, 0x6f, 0x82, 0x74, 0x76, 0x7f, 0xfb, 0xd6, 0xc4, 0xc3, 0xdd, 0xe8, 0xb1,
-0x60, 0xfc, 0xc6, 0xb9, 0x0d, 0x6a, 0x33, 0x78, 0xc6, 0xc1, 0xbf, 0x86, 0x2c, 0x50, 0xcc,
-0x9a, 0x70, 0x8e, 0x7b, 0xec, 0xab, 0x95, 0xac, 0x53, 0xa0, 0x4b, 0x07, 0x88, 0xaf, 0x42,
-0xed, 0x19, 0x8d, 0xf6, 0x32, 0x17, 0x48, 0x47, 0x1d, 0x41, 0x6f, 0xfe, 0x2e, 0xa7, 0x8f,
-0x4b, 0xa0, 0x51, 0xf3, 0xbf, 0x02, 0x0a, 0x48, 0x58, 0xf7, 0xa1, 0x6d, 0xea, 0xa5, 0x13,
-0x5a, 0x5b, 0xea, 0x0c, 0x9e, 0x52, 0x4f, 0x9e, 0xb9, 0x71, 0x7f, 0x23, 0x83, 0xda, 0x1b,
-0x86, 0x9a, 0x41, 0x29, 0xda, 0x70, 0xe7, 0x64, 0xa1, 0x7b, 0xd5, 0x0a, 0x22, 0x0d, 0x5c,
-0x40, 0xc4, 0x81, 0x07, 0x25, 0x35, 0x4a, 0x1c, 0x10, 0xdb, 0x45, 0x0a, 0xff, 0x36, 0xd4,
-0xe0, 0xeb, 0x5f, 0x68, 0xd6, 0x67, 0xc6, 0xd0, 0x8b, 0x76, 0x1a, 0x7d, 0x59, 0x42, 0xa1,
-0xcb, 0x96, 0x4d, 0x84, 0x09, 0x9a, 0x3d, 0xe0, 0x52, 0x85, 0x6e, 0x48, 0x90, 0x85, 0x2a,
-0x63, 0xb2, 0x69, 0xd2, 0x00, 0x43, 0x31, 0x37, 0xb3, 0x52, 0xaf, 0x62, 0xfa, 0xc1, 0xe0,
-0x03, 0xfb, 0x62, 0xaa, 0x88, 0xc9, 0xb2, 0x2c, 0xd5, 0xa8, 0xf5, 0xa5, 0x4c, 0x12, 0x59,
-0x4e, 0x06, 0x5e, 0x9b, 0x15, 0x66, 0x11, 0xb2, 0x27, 0x92, 0xdc, 0x98, 0x59, 0xde, 0xdf,
-0xfa, 0x9a, 0x32, 0x2e, 0xc0, 0x5d, 0x3c, 0x33, 0x41, 0x6d, 0xaf, 0xb2, 0x25, 0x23, 0x14,
-0xa5, 0x7b, 0xc7, 0x9b, 0x68, 0xf3, 0xda, 0xeb, 0xe3, 0xa9, 0xe2, 0x6f, 0x0e, 0x1d, 0x1c,
-0xba, 0x55, 0xb6, 0x34, 0x6a, 0x93, 0x1f, 0x1f, 0xb8, 0x34, 0xc8, 0x84, 0x08, 0xb1, 0x6b,
-0x6a, 0x28, 0x74, 0x74, 0xe5, 0xeb, 0x75, 0xe9, 0x7c, 0xd8, 0xba, 0xd8, 0x42, 0xa5, 0xee,
-0x1f, 0x80, 0xd9, 0x96, 0xb2, 0x2e, 0xe7, 0xbf, 0xba, 0xeb, 0xd1, 0x69, 0xbb, 0x8f, 0xfd,
-0x5a, 0x63, 0x8f, 0x39, 0x7f, 0xdf, 0x1d, 0x37, 0xd2, 0x18, 0x35, 0x9d, 0xb6, 0xcc, 0xe4,
-0x27, 0x81, 0x89, 0x38, 0x38, 0x68, 0x33, 0xe7, 0x78, 0xd8, 0x76, 0xf5, 0xee, 0xd0, 0x4a,
-0x07, 0x69, 0x19, 0x7a, 0xad, 0x18, 0xb1, 0x94, 0x61, 0x45, 0x53, 0xa2, 0x48, 0xda, 0x96,
-0x4a, 0xf9, 0xee, 0x94, 0x2a, 0x1f, 0x6e, 0x18, 0x3c, 0x92, 0x46, 0xd1, 0x1a, 0x28, 0x18,
-0x32, 0x1f, 0x3a, 0x45, 0xbe, 0x04, 0x35, 0x92, 0xe5, 0xa3, 0xcb, 0xb5, 0x2e, 0x32, 0x43,
-0xac, 0x65, 0x17, 0x89, 0x99, 0x15, 0x03, 0x9e, 0xb1, 0x23, 0x2f, 0xed, 0x76, 0x4d, 0xd8,
-0xac, 0x21, 0x40, 0xc4, 0x99, 0x4e, 0x65, 0x71, 0x2c, 0xb3, 0x45, 0xab, 0xfb, 0xe7, 0x72,
-0x39, 0x56, 0x30, 0x6d, 0xfb, 0x74, 0xeb, 0x99, 0xf3, 0xcd, 0x57, 0x5c, 0x78, 0x75, 0xe9,
-0x8d, 0xc3, 0xa2, 0xfb, 0x5d, 0xe0, 0x90, 0xc5, 0x55, 0xad, 0x91, 0x53, 0x4e, 0x9e, 0xbd,
-0x8c, 0x49, 0xa4, 0xa4, 0x69, 0x10, 0x0c, 0xc5, 0x76, 0xe9, 0x25, 0x86, 0x8d, 0x66, 0x23,
-0xa8, 0xdb, 0x5c, 0xe8, 0xd9, 0x30, 0xe1, 0x15, 0x7b, 0xc0, 0x99, 0x0f, 0x03, 0xec, 0xaa,
-0x12, 0xef, 0xce, 0xd4, 0xea, 0x55, 0x5c, 0x08, 0x86, 0xf4, 0xf4, 0xb0, 0x83, 0x42, 0x95,
-0x37, 0xb6, 0x38, 0xe0, 0x2b, 0x54, 0x89, 0xbd, 0x4e, 0x20, 0x9d, 0x3f, 0xc3, 0x4b, 0xb7,
-0xec, 0xfa, 0x5a, 0x14, 0x03, 0xcb, 0x64, 0xc8, 0x34, 0x4a, 0x4b, 0x6e, 0xf8, 0x6e, 0x56,
-0xf6, 0xdd, 0x5f, 0xa1, 0x24, 0xe2, 0xd4, 0xd0, 0x82, 0x64, 0x1f, 0x8e, 0x9b, 0xfa, 0xb4,
-0xcb, 0xdb, 0x0a, 0xe8, 0x15, 0xfc, 0x15, 0xab, 0x4b, 0x18, 0xbf, 0xd4, 0x42, 0x14, 0x48,
-0x82, 0x85, 0xdd, 0xeb, 0x49, 0x1b, 0x0b, 0x0b, 0x05, 0xe9, 0xb4, 0xa1, 0x33, 0x0a, 0x5d,
-0x0e, 0x6c, 0x4b, 0xc0, 0xd6, 0x6c, 0x7c, 0xfb, 0x69, 0x0b, 0x53, 0x19, 0xe4, 0xf3, 0x35,
-0xfc, 0xbe, 0xa1, 0x34, 0x02, 0x09, 0x4f, 0x74, 0x86, 0x92, 0xcd, 0x5d, 0x1a, 0xc1, 0x27,
-0x0c, 0xf2, 0xc5, 0xcf, 0xdd, 0x23, 0x93, 0x02, 0xbd, 0x41, 0x5e, 0x42, 0xf0, 0xa0, 0x9d,
-0x0c, 0x72, 0xc8, 0xec, 0x32, 0x0a, 0x8a, 0xfd, 0x3d, 0x5a, 0x41, 0x27, 0x0c, 0x88, 0x59,
-0xad, 0x94, 0x2e, 0xef, 0x5d, 0x8f, 0xc7, 0xdf, 0x66, 0xe4, 0xdd, 0x56, 0x6c, 0x7b, 0xca,
-0x55, 0x81, 0xae, 0xae, 0x5c, 0x1b, 0x1a, 0xab, 0xae, 0x99, 0x8d, 0xcc, 0x42, 0x97, 0x59,
-0xf4, 0x14, 0x3f, 0x75, 0xc6, 0xd1, 0x88, 0xba, 0xaa, 0x84, 0x4a, 0xd0, 0x34, 0x08, 0x3b,
-0x7d, 0xdb, 0x15, 0x06, 0xb0, 0x5c, 0xbd, 0x40, 0xf5, 0xa8, 0xec, 0xae, 0x36, 0x40, 0xdd,
-0x90, 0x1c, 0x3e, 0x0d, 0x7e, 0x73, 0xc7, 0xc2, 0xc5, 0x6a, 0xff, 0x52, 0x05, 0x7f, 0xbe,
-0xd0, 0x92, 0xfd, 0xb3, 0x6f, 0xff, 0x5d, 0xb7, 0x97, 0x64, 0x73, 0x7b, 0xca, 0xd1, 0x98,
-0x24, 0x6b, 0x0b, 0x01, 0x68, 0xdd, 0x27, 0x85, 0x85, 0xb5, 0x83, 0xc1, 0xe0, 0x50, 0x64,
-0xc7, 0xaf, 0xf1, 0xc6, 0x4d, 0xb1, 0xef, 0xc9, 0xb4, 0x0a, 0x6d, 0x65, 0xf3, 0x47, 0xcc,
-0xa3, 0x02, 0x21, 0x0c, 0xbe, 0x22, 0x29, 0x05, 0xcf, 0x5f, 0xe8, 0x94, 0x6c, 0xe5, 0xdc,
-0xc4, 0xdf, 0xbe, 0x3e, 0xa8, 0xb4, 0x18, 0xb0, 0x99, 0xb8, 0x6f, 0xff, 0x5d, 0xb9, 0xfd,
-0x3b, 0x5d, 0x16, 0xbf, 0x3e, 0xd8, 0xb3, 0xd8, 0x08, 0x34, 0xf6, 0x47, 0x35, 0x5b, 0x72,
-0x1a, 0x33, 0xad, 0x52, 0x5d, 0xb8, 0xd0, 0x77, 0xc6, 0xab, 0xba, 0x55, 0x09, 0x5f, 0x02,
-0xf8, 0xd4, 0x5f, 0x53, 0x06, 0x91, 0xcd, 0x74, 0x42, 0xae, 0x54, 0x91, 0x81, 0x62, 0x13,
-0x6f, 0xd8, 0xa9, 0x77, 0xc3, 0x6c, 0xcb, 0xf1, 0x29, 0x5a, 0xcc, 0xda, 0x35, 0xbd, 0x52,
-0x23, 0xbe, 0x59, 0xeb, 0x12, 0x6d, 0xb7, 0x53, 0xee, 0xfc, 0xb4, 0x1b, 0x13, 0x5e, 0xba,
-0x16, 0x7c, 0xc5, 0xf3, 0xe3, 0x6d, 0x07, 0x78, 0xf5, 0x2b, 0x21, 0x05, 0x88, 0x4c, 0xc0,
-0xa1, 0xe3, 0x36, 0x10, 0xf8, 0x1b, 0xd8, 0x17, 0xfb, 0x6a, 0x4e, 0xd8, 0xb3, 0x47, 0x2d,
-0x99, 0xbd, 0xbb, 0x5d, 0x37, 0x7d, 0xba, 0xf1, 0xe1, 0x7c, 0xc0, 0xc5, 0x54, 0x62, 0x7f,
-0xcf, 0x5a, 0x4a, 0x93, 0xcc, 0xf1, 0x1b, 0x34, 0xc8, 0xa6, 0x05, 0x4c, 0x55, 0x8b, 0x54,
-0x84, 0xd5, 0x77, 0xeb, 0xc0, 0x6d, 0x3a, 0x29, 0xbd, 0x75, 0x61, 0x09, 0x9a, 0x2c, 0xbb,
-0xf7, 0x18, 0x79, 0x34, 0x90, 0x24, 0xa5, 0x81, 0x70, 0x87, 0xc5, 0x02, 0x7c, 0xba, 0xd4,
-0x5e, 0x14, 0x8e, 0xe4, 0xed, 0xa2, 0x61, 0x6a, 0xb9, 0x6e, 0xb5, 0x4a, 0xb9, 0x01, 0x46,
-0xf4, 0xcf, 0xbc, 0x09, 0x2f, 0x27, 0x4b, 0xbd, 0x86, 0x7a, 0x10, 0xe1, 0xd4, 0xc8, 0xd9,
-0x20, 0x8d, 0x8a, 0x63, 0x00, 0x63, 0x44, 0xeb, 0x54, 0x0b, 0x75, 0x49, 0x10, 0xa2, 0xa7,
-0xad, 0xb9, 0xd1, 0x01, 0x80, 0x63, 0x25, 0xc8, 0x12, 0xa6, 0xce, 0x1e, 0xbe, 0xfe, 0x7e,
-0x5f, 0x3c, 0xdb, 0x34, 0xea, 0x37, 0xec, 0x3b, 0xd5, 0x28, 0xd2, 0x07, 0x8c, 0x9a, 0xb6,
-0xee, 0x5e, 0x3e, 0xdf, 0x1d, 0x99, 0xb0, 0xe2, 0x46, 0xef, 0x5c, 0x1b, 0xb4, 0xea, 0x56,
-0x2e, 0xde, 0x1f, 0x9d, 0xb8, 0xd3, 0x24, 0xab, 0xd4, 0x2a, 0xd6, 0x2e, 0xde, 0x1f, 0x9d,
-0xb8, 0xf2, 0x66, 0x2f, 0xbd, 0xf8, 0x72, 0x66, 0x4e, 0x1e, 0x9f, 0x9d, 0xb8, 0xf2, 0x47,
-0x0c, 0x9a, 0xb6, 0xee, 0x3f, 0xfc, 0x7a, 0x57, 0x0d, 0x79, 0x70, 0x62, 0x27, 0xad, 0xb9,
-0xd1, 0x01, 0x61, 0x40, 0x02, 0x67, 0x2d, 0xd8, 0x32, 0xe6, 0x2f, 0xdc, 0x3a, 0xd7, 0x2c,
-0xbb, 0xf4, 0x4b, 0xf5, 0x49, 0xf1, 0x60, 0x23, 0xc4, 0x0a, 0x77, 0x4d, 0xf9, 0x51, 0x01,
-0x80, 0x63, 0x25, 0xa9, 0xb1, 0xe0, 0x42, 0xe7, 0x4c, 0x1a, 0x97, 0xac, 0xbb, 0xf4, 0x6a,
-0x37, 0xcd, 0x18, 0xb2, 0xe6, 0x2f, 0xdc, 0x1b, 0x95, 0xa8, 0xd2, 0x07, 0x6d, 0x58, 0x32,
-0xe6, 0x4e, 0x1e, 0x9f, 0xbc, 0xfa, 0x57, 0x0d, 0x79, 0x51, 0x20, 0xc2, 0x06, 0x6f, 0x5c,
-0x1b, 0x95, 0xa8, 0xb3, 0xc5, 0xe9, 0x31, 0xe0, 0x23, 0xc4, 0x0a, 0x77, 0x4d, 0x18, 0x93,
-0x85, 0x69, 0x31, 0xc1, 0xe1, 0x21, 0xc0, 0xe3, 0x44, 0x0a, 0x77, 0x6c, 0x5a, 0x17, 0x8d,
-0x98, 0x93, 0xa4, 0xab, 0xd4, 0x2a, 0xb7, 0xec, 0x5a, 0x17, 0xac, 0xbb, 0xf4, 0x4b, 0x14,
-0xaa, 0xb7, 0xec, 0x3b, 0xd5, 0x28, 0xb3, 0xc5, 0xe9, 0x31, 0xc1, 0x00, 0x82, 0x67, 0x4c,
-0xfb, 0x55, 0x28, 0xd2, 0x26, 0xaf, 0xbd, 0xd9, 0x11, 0x81, 0x61, 0x21, 0xa1, 0xa1, 0xc0,
-0x02, 0x86, 0x6f, 0x5c, 0x1b, 0xb4, 0xcb, 0x14, 0x8b, 0x94, 0xaa, 0xd6, 0x2e, 0xbf, 0xdd,
-0x19, 0xb0, 0xe2, 0x46, 0x0e, 0x7f, 0x7c, 0x5b, 0x15, 0x89, 0x90, 0x83, 0x84, 0x6b, 0x54,
-0x0b, 0x75, 0x68, 0x52, 0x07, 0x6d, 0x58, 0x32, 0xc7, 0xed, 0x58, 0x32, 0xc7, 0xed, 0x58,
-0x32, 0xe6, 0x4e, 0xff, 0x7c, 0x7a, 0x76, 0x6e, 0x3f, 0xdd, 0x38, 0xd3, 0x05, 0x88, 0x92,
-0xa6, 0xaf, 0xdc, 0x1b, 0xb4, 0xcb, 0xf5, 0x68, 0x52, 0x07, 0x8c, 0x7b, 0x55, 0x09, 0x90,
-0x83, 0x84, 0x6b, 0x54, 0x2a, 0xb7, 0xec, 0x3b, 0xd5, 0x09, 0x90, 0xa2, 0xc6, 0x0e, 0x7f,
-0x7c, 0x7a, 0x57, 0x0d, 0x98, 0xb2, 0xc7, 0xed, 0x58, 0x32, 0xc7, 0x0c, 0x7b, 0x74, 0x4b,
-0x14, 0x8b, 0x94, 0xaa, 0xb7, 0xcd, 0x18, 0x93, 0xa4, 0xca, 0x16, 0xae, 0xbf, 0xdd, 0x19,
-0xb0, 0xe2, 0x46, 0x0e, 0x7f, 0x5d, 0x19, 0x91, 0x81, 0x80, 0x63, 0x44, 0xeb, 0x35, 0xc9,
-0x10, 0x83, 0x65, 0x48, 0x12, 0xa6, 0xce, 0x1e, 0x9f, 0xbc, 0xdb, 0x15, 0x89, 0x71, 0x60,
-0x23, 0xc4, 0xeb, 0x54, 0x2a, 0xb7, 0xec, 0x5a, 0x36, 0xcf, 0x81, 0x10, 0xac, 0x74 };
+const uint8_t firmware_data[FIRMWARE_LENGTH] PROGMEM = {
+ 0x01, 0xe8, 0xba, 0x26, 0x0b, 0xb2, 0xbe, 0xfe, 0x7e, 0x5f, 0x3c, 0xdb, 0x15, 0xa8, 0xb3,
+ 0xe4, 0x2b, 0xb5, 0xe8, 0x53, 0x07, 0x6d, 0x3b, 0xd1, 0x20, 0xc2, 0x06, 0x6f, 0x3d, 0xd9,
+ 0x11, 0xa0, 0xc2, 0xe7, 0x2d, 0xb9, 0xd1, 0x20, 0xa3, 0xa5, 0xc8, 0xf3, 0x64, 0x4a, 0xf7,
+ 0x4d, 0x18, 0x93, 0xa4, 0xca, 0xf7, 0x6c, 0x5a, 0x36, 0xee, 0x5e, 0x3e, 0xfe, 0x7e, 0x7e,
+ 0x5f, 0x1d, 0x99, 0xb0, 0xc3, 0xe5, 0x29, 0xd3, 0x03, 0x65, 0x48, 0x12, 0x87, 0x6d, 0x58,
+ 0x32, 0xe6, 0x2f, 0xdc, 0x3a, 0xf2, 0x4f, 0xfd, 0x59, 0x11, 0x81, 0x61, 0x21, 0xc0, 0x02,
+ 0x86, 0x8e, 0x7f, 0x5d, 0x38, 0xf2, 0x47, 0x0c, 0x7b, 0x55, 0x28, 0xb3, 0xe4, 0x4a, 0x16,
+ 0xab, 0xbf, 0xdd, 0x38, 0xf2, 0x66, 0x4e, 0xff, 0x5d, 0x19, 0x91, 0xa0, 0xa3, 0xa5, 0xc8,
+ 0x12, 0xa6, 0xaf, 0xdc, 0x3a, 0xd1, 0x41, 0x60, 0x75, 0x58, 0x24, 0x92, 0xd4, 0x72, 0x6c,
+ 0xe0, 0x2f, 0xfd, 0x23, 0x8d, 0x1c, 0x5b, 0xb2, 0x97, 0x36, 0x3d, 0x0b, 0xa2, 0x49, 0xb1,
+ 0x58, 0xf2, 0x1f, 0xc0, 0xcb, 0xf8, 0x41, 0x4f, 0xcd, 0x1e, 0x6b, 0x39, 0xa7, 0x2b, 0xe9,
+ 0x30, 0x16, 0x83, 0xd2, 0x0e, 0x47, 0x8f, 0xe3, 0xb1, 0xdf, 0xa2, 0x15, 0xdb, 0x5d, 0x30,
+ 0xc5, 0x1a, 0xab, 0x31, 0x99, 0xf3, 0xfa, 0xb2, 0x86, 0x69, 0xad, 0x7a, 0xe8, 0xa7, 0x18,
+ 0x6a, 0xcc, 0xc8, 0x65, 0x23, 0x87, 0xa8, 0x5f, 0xf5, 0x21, 0x59, 0x75, 0x09, 0x71, 0x45,
+ 0x55, 0x25, 0x4b, 0xda, 0xa1, 0xc3, 0xf7, 0x41, 0xab, 0x59, 0xd9, 0x74, 0x12, 0x55, 0x5f,
+ 0xbc, 0xaf, 0xd9, 0xfd, 0xb0, 0x1e, 0xa3, 0x0f, 0xff, 0xde, 0x11, 0x16, 0x6a, 0xae, 0x0e,
+ 0xe1, 0x5d, 0x3c, 0x10, 0x43, 0x9a, 0xa1, 0x0b, 0x24, 0x8f, 0x0d, 0x7f, 0x0b, 0x5e, 0x4c,
+ 0x42, 0xa4, 0x84, 0x2c, 0x40, 0xd0, 0x55, 0x39, 0xe6, 0x4b, 0xf8, 0x9b, 0x2f, 0xdc, 0x28,
+ 0xff, 0xfa, 0xb5, 0x85, 0x19, 0xe5, 0x28, 0xa1, 0x77, 0xaa, 0x73, 0xf3, 0x03, 0xc7, 0x62,
+ 0xa6, 0x91, 0x18, 0xc9, 0xb0, 0xcd, 0x05, 0xdc, 0xca, 0x81, 0x26, 0x1a, 0x47, 0x40, 0xda,
+ 0x36, 0x7d, 0x6a, 0x53, 0xc8, 0x5a, 0x77, 0x5d, 0x19, 0xa4, 0x1b, 0x23, 0x83, 0xd0, 0xb2,
+ 0xaa, 0x0e, 0xbf, 0x77, 0x4e, 0x3a, 0x3b, 0x59, 0x00, 0x31, 0x0d, 0x02, 0x1b, 0x88, 0x7a,
+ 0xd4, 0xbd, 0x9d, 0xcc, 0x58, 0x04, 0x69, 0xf6, 0x3b, 0xca, 0x42, 0xe2, 0xfd, 0xc3, 0x3d,
+ 0x39, 0xc5, 0xd0, 0x71, 0xe4, 0xc8, 0xb7, 0x3e, 0x3f, 0xc8, 0xe9, 0xca, 0xc9, 0x3f, 0x04,
+ 0x4e, 0x1b, 0x79, 0xca, 0xa5, 0x61, 0xc2, 0xed, 0x1d, 0xa6, 0xda, 0x5a, 0xe9, 0x7f, 0x65,
+ 0x8c, 0xbe, 0x12, 0x6e, 0xa4, 0x5b, 0x33, 0x2f, 0x84, 0x28, 0x9c, 0x1c, 0x88, 0x2d, 0xff,
+ 0x07, 0xbf, 0xa6, 0xd7, 0x5a, 0x88, 0x86, 0xb0, 0x3f, 0xf6, 0x31, 0x5b, 0x11, 0x6d, 0xf5,
+ 0x58, 0xeb, 0x58, 0x02, 0x9e, 0xb5, 0x9a, 0xb1, 0xff, 0x25, 0x9d, 0x8b, 0x4f, 0xb6, 0x0a,
+ 0xf9, 0xea, 0x3e, 0x3f, 0x21, 0x09, 0x65, 0x21, 0x22, 0xfe, 0x3d, 0x4e, 0x11, 0x5b, 0x9e,
+ 0x5a, 0x59, 0x8b, 0xdd, 0xd8, 0xce, 0xd6, 0xd9, 0x59, 0xd2, 0x1e, 0xfd, 0xef, 0x0d, 0x1b,
+ 0xd9, 0x61, 0x7f, 0xd7, 0x2d, 0xad, 0x62, 0x09, 0xe5, 0x22, 0x63, 0xea, 0xc7, 0x31, 0xd9,
+ 0xa1, 0x38, 0x80, 0x5c, 0xa7, 0x32, 0x82, 0xec, 0x1b, 0xa2, 0x49, 0x5a, 0x06, 0xd2, 0x7c,
+ 0xc9, 0x96, 0x57, 0xbb, 0x17, 0x75, 0xfc, 0x7a, 0x8f, 0x0d, 0x77, 0xb5, 0x7a, 0x8e, 0x3e,
+ 0xf4, 0xba, 0x2f, 0x69, 0x13, 0x26, 0xd6, 0xd9, 0x21, 0x60, 0x2f, 0x21, 0x3e, 0x87, 0xee,
+ 0xfd, 0x87, 0x16, 0x0d, 0xc8, 0x08, 0x00, 0x25, 0x71, 0xac, 0x2c, 0x03, 0x2a, 0x37, 0x2d,
+ 0xb3, 0x34, 0x09, 0x91, 0xe3, 0x06, 0x2c, 0x38, 0x37, 0x95, 0x3b, 0x17, 0x7a, 0xaf, 0xac,
+ 0x99, 0x55, 0xab, 0x41, 0x39, 0x5f, 0x8e, 0xa6, 0x43, 0x80, 0x03, 0x88, 0x6f, 0x7d, 0xbd,
+ 0x5a, 0xb4, 0x2b, 0x32, 0x23, 0x5a, 0xa9, 0x31, 0x32, 0x39, 0x4c, 0x5b, 0xf4, 0x6b, 0xaf,
+ 0x66, 0x6f, 0x3c, 0x8e, 0x2d, 0x82, 0x97, 0x9f, 0x4a, 0x01, 0xdc, 0x99, 0x98, 0x00, 0xec,
+ 0x38, 0x7a, 0x79, 0x70, 0xa6, 0x85, 0xd6, 0x21, 0x63, 0x0d, 0x45, 0x9a, 0x2e, 0x5e, 0xa7,
+ 0xb1, 0xea, 0x66, 0x6a, 0xbc, 0x62, 0x2d, 0x7b, 0x7d, 0x85, 0xea, 0x95, 0x2f, 0xc0, 0xe8,
+ 0x6f, 0x35, 0xa0, 0x3a, 0x02, 0x25, 0xbc, 0xb2, 0x5f, 0x5c, 0x43, 0x96, 0xcc, 0x26, 0xd2,
+ 0x16, 0xb4, 0x96, 0x73, 0xd7, 0x13, 0xc7, 0xae, 0x53, 0x15, 0x31, 0x89, 0x68, 0x66, 0x6d,
+ 0x2c, 0x92, 0x1f, 0xcc, 0x5b, 0xa7, 0x8f, 0x5d, 0xbb, 0xc9, 0xdb, 0xe8, 0x3b, 0x9d, 0x61,
+ 0x74, 0x8b, 0x05, 0xa1, 0x58, 0x52, 0x68, 0xee, 0x3d, 0x39, 0x79, 0xa0, 0x9b, 0xdd, 0xe1,
+ 0x55, 0xc9, 0x60, 0xeb, 0xad, 0xb8, 0x5b, 0xc2, 0x5a, 0xb5, 0x2c, 0x18, 0x55, 0xa9, 0x50,
+ 0xc3, 0xf6, 0x72, 0x5f, 0xcc, 0xe2, 0xf4, 0x55, 0xb5, 0xd6, 0xb5, 0x4a, 0x99, 0xa5, 0x28,
+ 0x74, 0x97, 0x18, 0xe8, 0xc0, 0x84, 0x89, 0x50, 0x03, 0x86, 0x4d, 0x1a, 0xb7, 0x09, 0x90,
+ 0xa2, 0x01, 0x04, 0xbb, 0x73, 0x62, 0xcb, 0x97, 0x22, 0x70, 0x5d, 0x52, 0x41, 0x8e, 0xd9,
+ 0x90, 0x15, 0xaa, 0xab, 0x0a, 0x31, 0x65, 0xb4, 0xda, 0xd0, 0xee, 0x24, 0xc9, 0x41, 0x91,
+ 0x1e, 0xbc, 0x46, 0x70, 0x40, 0x9d, 0xda, 0x0e, 0x2a, 0xe4, 0xb2, 0x4c, 0x9f, 0xf2, 0xfc,
+ 0xf3, 0x84, 0x17, 0x44, 0x1e, 0xd7, 0xca, 0x23, 0x1f, 0x3f, 0x5a, 0x22, 0x3d, 0xaf, 0x9b,
+ 0x2d, 0xfc, 0x41, 0xad, 0x26, 0xb4, 0x45, 0x67, 0x0b, 0x80, 0x0e, 0xf9, 0x61, 0x37, 0xec,
+ 0x3b, 0xf4, 0x4b, 0x14, 0xdf, 0x5a, 0x0c, 0x3a, 0x50, 0x0b, 0x14, 0x0c, 0x72, 0xae, 0xc6,
+ 0xc5, 0xec, 0x35, 0x53, 0x2d, 0x59, 0xed, 0x91, 0x74, 0xe2, 0xc4, 0xc8, 0xf2, 0x25, 0x6b,
+ 0x97, 0x6f, 0xc9, 0x76, 0xce, 0xa9, 0xb1, 0x99, 0x8f, 0x5a, 0x92, 0x3b, 0xc4, 0x8d, 0x54,
+ 0x50, 0x40, 0x72, 0xd6, 0x90, 0x83, 0xfc, 0xe5, 0x49, 0x8b, 0x17, 0xf5, 0xfd, 0x6b, 0x8d,
+ 0x32, 0x02, 0xe9, 0x0a, 0xfe, 0xbf, 0x00, 0x6b, 0xa3, 0xad, 0x5f, 0x09, 0x4b, 0x97, 0x2b,
+ 0x00, 0x58, 0x65, 0x2e, 0x07, 0x49, 0x0a, 0x3b, 0x6b, 0x2e, 0x50, 0x6c, 0x1d, 0xac, 0xb7,
+ 0x6a, 0x26, 0xd8, 0x13, 0xa4, 0xca, 0x16, 0xae, 0xab, 0x93, 0xb9, 0x1c, 0x1c, 0xb4, 0x47,
+ 0x6a, 0x38, 0x36, 0x17, 0x27, 0xc9, 0x7f, 0xc7, 0x64, 0xcb, 0x89, 0x58, 0xc5, 0x61, 0xc2,
+ 0xc6, 0xea, 0x15, 0x0b, 0x34, 0x0c, 0x5d, 0x61, 0x76, 0x6e, 0x2b, 0x62, 0x40, 0x92, 0xa3,
+ 0x6c, 0xef, 0xf4, 0xe4, 0xc3, 0xa1, 0xa8, 0xf5, 0x94, 0x79, 0x0d, 0xd1, 0x3d, 0xcb, 0x3d,
+ 0x40, 0xb6, 0xd0, 0xf0, 0x10, 0x54, 0xd8, 0x47, 0x25, 0x51, 0xc5, 0x41, 0x79, 0x00, 0xe5,
+ 0xa0, 0x72, 0xde, 0xbb, 0x3b, 0x62, 0x17, 0xf6, 0xbc, 0x5d, 0x00, 0x76, 0x2e, 0xa7, 0x3b,
+ 0xb6, 0xf1, 0x98, 0x72, 0x59, 0x2a, 0x73, 0xb0, 0x21, 0xd6, 0x49, 0xe0, 0xc0, 0xd5, 0xeb,
+ 0x02, 0x7d, 0x4b, 0x41, 0x28, 0x70, 0x2d, 0xec, 0x2b, 0x71, 0x1f, 0x0b, 0xb9, 0x71, 0x63,
+ 0x06, 0xe6, 0xbc, 0x60, 0xbb, 0xf4, 0x9a, 0x62, 0x43, 0x09, 0x18, 0x4e, 0x93, 0x06, 0x4d,
+ 0x76, 0xfa, 0x7f, 0xbd, 0x02, 0xe4, 0x50, 0x91, 0x12, 0xe5, 0x86, 0xff, 0x64, 0x1e, 0xaf,
+ 0x7e, 0xb3, 0xb2, 0xde, 0x89, 0xc1, 0xa2, 0x6f, 0x40, 0x7b, 0x41, 0x51, 0x63, 0xea, 0x25,
+ 0xd1, 0x97, 0x57, 0x92, 0xa8, 0x45, 0xa1, 0xa5, 0x45, 0x21, 0x43, 0x7f, 0x83, 0x15, 0x29,
+ 0xd0, 0x30, 0x53, 0x32, 0xb4, 0x5a, 0x17, 0x96, 0xbc, 0xc2, 0x68, 0xa9, 0xb7, 0xaf, 0xac,
+ 0xdf, 0xf1, 0xe3, 0x89, 0xba, 0x24, 0x79, 0x54, 0xc6, 0x14, 0x07, 0x1c, 0x1e, 0x0d, 0x3a,
+ 0x6b, 0xe5, 0x3d, 0x4e, 0x10, 0x60, 0x96, 0xec, 0x6c, 0xda, 0x47, 0xae, 0x03, 0x25, 0x39,
+ 0x1d, 0x74, 0xc8, 0xac, 0x6a, 0xf2, 0x6b, 0x05, 0x2a, 0x9a, 0xe7, 0xe8, 0x92, 0xd6, 0xc2,
+ 0x6d, 0xfa, 0xe8, 0xa7, 0x9d, 0x5f, 0x48, 0xc9, 0x75, 0xf1, 0x66, 0x6a, 0xdb, 0x5d, 0x9a,
+ 0xcd, 0x27, 0xdd, 0xb9, 0x24, 0x04, 0x9c, 0x18, 0xc2, 0x6d, 0x0c, 0x91, 0x34, 0x48, 0x42,
+ 0x6f, 0xe9, 0x59, 0x70, 0xc4, 0x7e, 0x81, 0x0e, 0x32, 0x0a, 0x93, 0x48, 0xb0, 0xc0, 0x15,
+ 0x9e, 0x05, 0xac, 0x36, 0x16, 0xcb, 0x59, 0x65, 0xa0, 0x83, 0xdf, 0x3e, 0xda, 0xfb, 0x1d,
+ 0x1a, 0xdb, 0x65, 0xec, 0x9a, 0xc6, 0xc3, 0x8e, 0x3c, 0x45, 0xfd, 0xc8, 0xf5, 0x1c, 0x6a,
+ 0x67, 0x0d, 0x8f, 0x99, 0x7d, 0x30, 0x21, 0x8c, 0xea, 0x22, 0x87, 0x65, 0xc9, 0xb2, 0x4c,
+ 0xe4, 0x1b, 0x46, 0xba, 0x54, 0xbd, 0x7c, 0xca, 0xd5, 0x8f, 0x5b, 0xa5, 0x01, 0x04, 0xd8,
+ 0x0a, 0x16, 0xbf, 0xb9, 0x50, 0x2e, 0x37, 0x2f, 0x64, 0xf3, 0x70, 0x11, 0x02, 0x05, 0x31,
+ 0x9b, 0xa0, 0xb2, 0x01, 0x5e, 0x4f, 0x19, 0xc9, 0xd4, 0xea, 0xa1, 0x79, 0x54, 0x53, 0xa7,
+ 0xde, 0x2f, 0x49, 0xd3, 0xd1, 0x63, 0xb5, 0x03, 0x15, 0x4e, 0xbf, 0x04, 0xb3, 0x26, 0x8b,
+ 0x20, 0xb2, 0x45, 0xcf, 0xcd, 0x5b, 0x82, 0x32, 0x88, 0x61, 0xa7, 0xa8, 0xb2, 0xa0, 0x72,
+ 0x96, 0xc0, 0xdb, 0x2b, 0xe2, 0x5f, 0xba, 0xe3, 0xf5, 0x8a, 0xde, 0xf1, 0x18, 0x01, 0x16,
+ 0x40, 0xd9, 0x86, 0x12, 0x09, 0x18, 0x1b, 0x05, 0x0c, 0xb1, 0xb5, 0x47, 0xe2, 0x43, 0xab,
+ 0xfe, 0x92, 0x63, 0x7e, 0x95, 0x2b, 0xf0, 0xaf, 0xe1, 0xf1, 0xc3, 0x4a, 0xff, 0x2b, 0x09,
+ 0xbb, 0x4a, 0x0e, 0x9a, 0xc4, 0xd8, 0x64, 0x7d, 0x83, 0xa0, 0x4f, 0x44, 0xdb, 0xc4, 0xa8,
+ 0x58, 0xef, 0xfc, 0x9e, 0x77, 0xf9, 0xa6, 0x8f, 0x58, 0x8b, 0x12, 0xf4, 0xe9, 0x81, 0x12,
+ 0x47, 0x51, 0x41, 0x83, 0xef, 0xf6, 0x73, 0xbc, 0x8e, 0x0f, 0x4c, 0x8f, 0x4e, 0x69, 0x90,
+ 0x77, 0x29, 0x5d, 0x92, 0xb0, 0x6d, 0x06, 0x67, 0x29, 0x60, 0xbd, 0x4b, 0x17, 0xc8, 0x89,
+ 0x69, 0x28, 0x29, 0xd6, 0x78, 0xcb, 0x11, 0x4c, 0xba, 0x8b, 0x68, 0xae, 0x7e, 0x9f, 0xef,
+ 0x95, 0xda, 0xe2, 0x9e, 0x7f, 0xe9, 0x55, 0xe5, 0xe1, 0xe2, 0xb7, 0xe6, 0x5f, 0xbb, 0x2c,
+ 0xa2, 0xe6, 0xee, 0xc7, 0x0a, 0x60, 0xa9, 0xd1, 0x80, 0xdf, 0x7f, 0xd6, 0x97, 0xab, 0x1d,
+ 0x22, 0x25, 0xfc, 0x79, 0x23, 0xe0, 0xae, 0xc5, 0xef, 0x16, 0xa4, 0xa1, 0x0f, 0x92, 0xa9,
+ 0xc7, 0xe3, 0x3a, 0x55, 0xdf, 0x62, 0x49, 0xd9, 0xf5, 0x84, 0x49, 0xc5, 0x90, 0x34, 0xd3,
+ 0xe1, 0xac, 0x99, 0x21, 0xb1, 0x02, 0x76, 0x4a, 0xfa, 0xd4, 0xbb, 0xa4, 0x9c, 0xa2, 0xe2,
+ 0xcb, 0x3d, 0x3b, 0x14, 0x75, 0x60, 0xd1, 0x02, 0xb4, 0xa3, 0xb4, 0x72, 0x06, 0xf9, 0x19,
+ 0x9c, 0xe2, 0xe4, 0xa7, 0x0f, 0x25, 0x88, 0xc6, 0x86, 0xd6, 0x8c, 0x74, 0x4e, 0x6e, 0xfc,
+ 0xa8, 0x48, 0x9e, 0xa7, 0x9d, 0x1a, 0x4b, 0x37, 0x09, 0xc8, 0xb0, 0x10, 0xbe, 0x6f, 0xfe,
+ 0xa3, 0xc4, 0x7a, 0xb5, 0x3d, 0xe8, 0x30, 0xf1, 0x0d, 0xa0, 0xb2, 0x44, 0xfc, 0x9b, 0x8c,
+ 0xf8, 0x61, 0xed, 0x81, 0xd1, 0x62, 0x11, 0xb4, 0xe1, 0xd5, 0x39, 0x52, 0x89, 0xd3, 0xa8,
+ 0x49, 0x31, 0xdf, 0xb6, 0xf9, 0x91, 0xf4, 0x1c, 0x9d, 0x09, 0x95, 0x40, 0x56, 0xe7, 0xe3,
+ 0xcd, 0x5c, 0x92, 0xc1, 0x1d, 0x6b, 0xe9, 0x78, 0x6f, 0x8e, 0x94, 0x42, 0x66, 0xa2, 0xaa,
+ 0xd3, 0xc8, 0x2e, 0xe3, 0xf6, 0x07, 0x72, 0x0b, 0x6b, 0x1e, 0x7b, 0xb9, 0x7c, 0xe0, 0xa0,
+ 0xbc, 0xd9, 0x25, 0xdf, 0x87, 0xa8, 0x5f, 0x9c, 0xcc, 0xf0, 0xdb, 0x42, 0x8e, 0x07, 0x31,
+ 0x13, 0x01, 0x66, 0x32, 0xd1, 0xb8, 0xd6, 0xe3, 0x5e, 0x12, 0x76, 0x61, 0xd3, 0x38, 0x89,
+ 0xe6, 0x17, 0x6f, 0xa5, 0xf2, 0x71, 0x0e, 0xa5, 0xe2, 0x88, 0x30, 0xbb, 0xbe, 0x8a, 0xea,
+ 0xc7, 0x62, 0xc4, 0xcf, 0xb8, 0xcd, 0x33, 0x8d, 0x3d, 0x3e, 0xb5, 0x60, 0x3a, 0x03, 0x92,
+ 0xe4, 0x6d, 0x1b, 0xe0, 0xb4, 0x84, 0x08, 0x55, 0x88, 0xa7, 0x3a, 0xb9, 0x3d, 0x43, 0xc3,
+ 0xc0, 0xfa, 0x07, 0x6a, 0xca, 0x94, 0xad, 0x99, 0x55, 0xf1, 0xf1, 0xc0, 0x23, 0x87, 0x1d,
+ 0x3d, 0x1c, 0xd1, 0x66, 0xa0, 0x57, 0x10, 0x52, 0xa2, 0x7f, 0xbe, 0xf9, 0x88, 0xb6, 0x02,
+ 0xbf, 0x08, 0x23, 0xa9, 0x0c, 0x63, 0x17, 0x2a, 0xae, 0xf5, 0xf7, 0xb7, 0x21, 0x83, 0x92,
+ 0x31, 0x23, 0x0d, 0x20, 0xc3, 0xc2, 0x05, 0x21, 0x62, 0x8e, 0x45, 0xe8, 0x14, 0xc1, 0xda,
+ 0x75, 0xb8, 0xf8, 0x92, 0x01, 0xd0, 0x5d, 0x18, 0x9f, 0x99, 0x11, 0x19, 0xf5, 0x35, 0xe8,
+ 0x7f, 0x20, 0x88, 0x8c, 0x05, 0x75, 0xf5, 0xd7, 0x40, 0x17, 0xbb, 0x1e, 0x36, 0x52, 0xd9,
+ 0xa4, 0x9c, 0xc2, 0x9d, 0x42, 0x81, 0xd8, 0xc7, 0x8a, 0xe7, 0x4c, 0x81, 0xe0, 0xb7, 0x57,
+ 0xed, 0x48, 0x8b, 0xf0, 0x97, 0x15, 0x61, 0xd9, 0x2c, 0x7c, 0x45, 0xaf, 0xc2, 0xcd, 0xfc,
+ 0xaa, 0x13, 0xad, 0x59, 0xcc, 0xb2, 0xb2, 0x6e, 0xdd, 0x63, 0x9c, 0x32, 0x0f, 0xec, 0x83,
+ 0xbe, 0x78, 0xac, 0x91, 0x44, 0x1a, 0x1f, 0xea, 0xfd, 0x5d, 0x8e, 0xb4, 0xc0, 0x84, 0xd4,
+ 0xac, 0xb4, 0x87, 0x5f, 0xac, 0xef, 0xdf, 0xcd, 0x12, 0x56, 0xc8, 0xcd, 0xfe, 0xc5, 0xda,
+ 0xd3, 0xc1, 0x69, 0xf3, 0x61, 0x05, 0xea, 0x25, 0xe2, 0x12, 0x05, 0x8f, 0x39, 0x08, 0x08,
+ 0x7c, 0x37, 0xb6, 0x7e, 0x5b, 0xd8, 0xb1, 0x0e, 0xf2, 0xdb, 0x4b, 0xf1, 0xad, 0x90, 0x01,
+ 0x57, 0xcd, 0xa0, 0xb4, 0x52, 0xe8, 0xf3, 0xd7, 0x8a, 0xbd, 0x4f, 0x9f, 0x21, 0x40, 0x72,
+ 0xa4, 0xfc, 0x0b, 0x01, 0x2b, 0x2f, 0xb6, 0x4c, 0x95, 0x2d, 0x35, 0x33, 0x41, 0x6b, 0xa0,
+ 0x93, 0xe7, 0x2c, 0xf2, 0xd3, 0x72, 0x8b, 0xf4, 0x4f, 0x15, 0x3c, 0xaf, 0xd6, 0x12, 0xde,
+ 0x3f, 0x83, 0x3f, 0xff, 0xf8, 0x7f, 0xf6, 0xcc, 0xa6, 0x7f, 0xc9, 0x9a, 0x6e, 0x1f, 0xc1,
+ 0x0c, 0xfb, 0xee, 0x9c, 0xe7, 0xaf, 0xc9, 0x26, 0x54, 0xef, 0xb0, 0x39, 0xef, 0xb2, 0xe9,
+ 0x23, 0xc4, 0xef, 0xd1, 0xa1, 0xa4, 0x25, 0x24, 0x6f, 0x8d, 0x6a, 0xe5, 0x8a, 0x32, 0x3a,
+ 0xaf, 0xfc, 0xda, 0xce, 0x18, 0x25, 0x42, 0x07, 0x4d, 0x45, 0x8b, 0xdf, 0x85, 0xcf, 0x55,
+ 0xb2, 0x24, 0xfe, 0x9c, 0x69, 0x74, 0xa7, 0x6e, 0xa0, 0xce, 0xc0, 0x39, 0xf4, 0x86, 0xc6,
+ 0x8d, 0xae, 0xb9, 0x48, 0x64, 0x13, 0x0b, 0x40, 0x81, 0xa2, 0xc9, 0xa8, 0x85, 0x51, 0xee,
+ 0x9f, 0xcf, 0xa2, 0x8c, 0x19, 0x52, 0x48, 0xe2, 0xc1, 0xa8, 0x58, 0xb4, 0x10, 0x24, 0x06,
+ 0x58, 0x51, 0xfc, 0xb9, 0x12, 0xec, 0xfd, 0x73, 0xb4, 0x6d, 0x84, 0xfa, 0x06, 0x8b, 0x05,
+ 0x0b, 0x2d, 0xd6, 0xd6, 0x1f, 0x29, 0x82, 0x9f, 0x19, 0x12, 0x1e, 0xb2, 0x04, 0x8f, 0x7f,
+ 0x4d, 0xbd, 0x30, 0x2e, 0xe3, 0xe0, 0x88, 0x29, 0xc5, 0x93, 0xd6, 0x6c, 0x1f, 0x29, 0x45,
+ 0x91, 0xa7, 0x58, 0xcd, 0x05, 0x17, 0xd6, 0x6d, 0xb3, 0xca, 0x66, 0xcc, 0x3c, 0x4a, 0x74,
+ 0xfd, 0x08, 0x10, 0xa6, 0x99, 0x92, 0x10, 0xd2, 0x85, 0xab, 0x6e, 0x1d, 0x0e, 0x8b, 0x26,
+ 0x46, 0xd1, 0x6c, 0x84, 0xc0, 0x26, 0x43, 0x59, 0x68, 0xf0, 0x13, 0x1d, 0xfb, 0xe3, 0xd1,
+ 0xd2, 0xb4, 0x71, 0x9e, 0xf2, 0x59, 0x6a, 0x33, 0x29, 0x79, 0xd2, 0xd7, 0x26, 0xf1, 0xae,
+ 0x78, 0x9e, 0x1f, 0x0f, 0x3f, 0xe3, 0xe8, 0xd0, 0x27, 0x78, 0x77, 0xf6, 0xac, 0x9c, 0x56,
+ 0x39, 0x73, 0x8a, 0x6b, 0x2f, 0x34, 0x78, 0xb1, 0x11, 0xdb, 0xa4, 0x5c, 0x80, 0x01, 0x71,
+ 0x6a, 0xc2, 0xd1, 0x2e, 0x5e, 0x76, 0x28, 0x70, 0x93, 0xae, 0x3e, 0x78, 0xb0, 0x1f, 0x0f,
+ 0xda, 0xbf, 0xfb, 0x8a, 0x67, 0x65, 0x4f, 0x91, 0xed, 0x49, 0x75, 0x78, 0x62, 0xa2, 0x93,
+ 0xb5, 0x70, 0x7f, 0x4d, 0x08, 0x4e, 0x79, 0x61, 0xa8, 0x5f, 0x7f, 0xb4, 0x65, 0x9f, 0x91,
+ 0x54, 0x3a, 0xe8, 0x50, 0x33, 0xd3, 0xd5, 0x8a, 0x7c, 0xf3, 0x9e, 0x8b, 0x77, 0x7b, 0xc6,
+ 0xc6, 0x0c, 0x45, 0x95, 0x1f, 0xb0, 0xd0, 0x0b, 0x27, 0x4a, 0xfd, 0xc7, 0xf7, 0x0d, 0x5a,
+ 0x43, 0xc9, 0x7d, 0x35, 0xb0, 0x7d, 0xc4, 0x9c, 0x57, 0x1e, 0x76, 0x0d, 0xf1, 0x95, 0x30,
+ 0x71, 0xcc, 0xb3, 0x66, 0x3b, 0x63, 0xa8, 0x6c, 0xa3, 0x43, 0xa0, 0x24, 0xcc, 0xb7, 0x53,
+ 0xfe, 0xfe, 0xbc, 0x6e, 0x60, 0x89, 0xaf, 0x16, 0x21, 0xc8, 0x91, 0x6a, 0x89, 0xce, 0x80,
+ 0x2c, 0xf1, 0x59, 0xce, 0xc3, 0x60, 0x61, 0x3b, 0x0b, 0x19, 0xfe, 0x99, 0xac, 0x65, 0x90,
+ 0x15, 0x12, 0x05, 0xac, 0x7e, 0xff, 0x98, 0x7b, 0x66, 0x64, 0x0e, 0x4b, 0x5b, 0xaa, 0x8d,
+ 0x3b, 0xd2, 0x56, 0xcf, 0x99, 0x39, 0xee, 0x22, 0x81, 0xd0, 0x60, 0x06, 0x66, 0x20, 0x81,
+ 0x48, 0x3c, 0x6f, 0x3a, 0x77, 0xba, 0xcb, 0x52, 0xac, 0x79, 0x56, 0xaf, 0xe9, 0x16, 0x17,
+ 0x0a, 0xa3, 0x82, 0x08, 0xd5, 0x3c, 0x97, 0xcb, 0x09, 0xff, 0x7f, 0xf9, 0x4f, 0x60, 0x05,
+ 0xb9, 0x53, 0x26, 0xaa, 0xb8, 0x50, 0xaa, 0x19, 0x25, 0xae, 0x5f, 0xea, 0x8a, 0xd0, 0x89,
+ 0x12, 0x80, 0x43, 0x50, 0x24, 0x12, 0x21, 0x14, 0xcd, 0x77, 0xeb, 0x21, 0xcc, 0x5c, 0x09,
+ 0x64, 0xf3, 0xc7, 0xcb, 0xc5, 0x4b, 0xc3, 0xe7, 0xed, 0xe7, 0x86, 0x2c, 0x1d, 0x8e, 0x19,
+ 0x52, 0x9b, 0x2a, 0x0c, 0x18, 0x72, 0x0b, 0x1e, 0x1b, 0xb0, 0x0f, 0x42, 0x99, 0x04, 0xae,
+ 0xd5, 0xb7, 0x89, 0x1a, 0xb9, 0x4f, 0xd6, 0xaf, 0xf3, 0xc9, 0x93, 0x6f, 0xb0, 0x60, 0x83,
+ 0x6e, 0x6b, 0xd1, 0x5f, 0x3f, 0x1a, 0x83, 0x1e, 0x24, 0x00, 0x87, 0xb5, 0x3e, 0xdb, 0xf9,
+ 0x4d, 0xa7, 0x16, 0x2e, 0x19, 0x5b, 0x8f, 0x1b, 0x0d, 0x47, 0x72, 0x42, 0xe9, 0x0a, 0x11,
+ 0x08, 0x2d, 0x88, 0x1c, 0xbc, 0xc7, 0xb4, 0xbe, 0x29, 0x4d, 0x03, 0x5e, 0xec, 0xdf, 0xf3,
+ 0x3d, 0x2f, 0xe8, 0x1d, 0x9a, 0xd2, 0xd1, 0xab, 0x41, 0x3d, 0x87, 0x11, 0x45, 0xb0, 0x0d,
+ 0x46, 0xf5, 0xe8, 0x95, 0x62, 0x1c, 0x68, 0xf7, 0xa6, 0x5b, 0x39, 0x4e, 0xbf, 0x47, 0xba,
+ 0x5d, 0x7f, 0xb7, 0x6a, 0xf4, 0xba, 0x1d, 0x69, 0xf6, 0xa4, 0xe7, 0xe4, 0x6b, 0x3b, 0x0d,
+ 0x23, 0x16, 0x4a, 0xb2, 0x68, 0xf0, 0xb2, 0x0d, 0x09, 0x17, 0x6a, 0x63, 0x8c, 0x83, 0xd3,
+ 0xbd, 0x05, 0xc9, 0xf6, 0xf0, 0xa1, 0x31, 0x0b, 0x2c, 0xac, 0x83, 0xac, 0x80, 0x34, 0x32,
+ 0xb4, 0xec, 0xd0, 0xbc, 0x54, 0x82, 0x9a, 0xc8, 0xf6, 0xa0, 0x7d, 0xc6, 0x79, 0x73, 0xf4,
+ 0x20, 0x99, 0xf3, 0xb4, 0x01, 0xde, 0x91, 0x27, 0xf2, 0xc0, 0xdc, 0x81, 0x00, 0x4e, 0x7e,
+ 0x07, 0x99, 0xc8, 0x3a, 0x51, 0xbc, 0x38, 0xd6, 0x8a, 0xa2, 0xde, 0x3b, 0x6a, 0x8c, 0x1a,
+ 0x7c, 0x81, 0x0f, 0x3a, 0x1f, 0xe4, 0x05, 0x7b, 0x20, 0x35, 0x6b, 0xa5, 0x6a, 0xa7, 0xe7,
+ 0xbc, 0x9c, 0x20, 0xec, 0x00, 0x15, 0xe2, 0x51, 0xaf, 0x77, 0xeb, 0x29, 0x3c, 0x7d, 0x2e,
+ 0x00, 0x5c, 0x81, 0x21, 0xfa, 0x35, 0x6f, 0x40, 0xef, 0xfb, 0xd1, 0x3f, 0xcc, 0x9d, 0x55,
+ 0x53, 0xfb, 0x5a, 0xa5, 0x56, 0x89, 0x0b, 0x52, 0xeb, 0x57, 0x73, 0x4f, 0x1b, 0x67, 0x24,
+ 0xcb, 0xb8, 0x6a, 0x10, 0x69, 0xd6, 0xfb, 0x52, 0x40, 0xff, 0x20, 0xa5, 0xf3, 0x72, 0xe1,
+ 0x3d, 0xa4, 0x8c, 0x81, 0x66, 0x16, 0x0d, 0x5d, 0xad, 0xa8, 0x50, 0x25, 0x78, 0x31, 0x77,
+ 0x0c, 0x57, 0xe4, 0xe9, 0x15, 0x2d, 0xdb, 0x07, 0x87, 0xc8, 0xb0, 0x43, 0xde, 0xfc, 0xfe,
+ 0xa9, 0xeb, 0xf5, 0xb0, 0xd3, 0x7b, 0xe9, 0x1f, 0x6e, 0xca, 0xe4, 0x03, 0x95, 0xc5, 0xd1,
+ 0x59, 0x72, 0x63, 0xf0, 0x86, 0x54, 0xe8, 0x16, 0x62, 0x0b, 0x35, 0x29, 0xc2, 0x68, 0xd0,
+ 0xd6, 0x3e, 0x90, 0x60, 0x57, 0x1d, 0xc9, 0xed, 0x3f, 0xed, 0xb0, 0x2f, 0x7e, 0x97, 0x02,
+ 0x51, 0xec, 0xee, 0x6f, 0x82, 0x74, 0x76, 0x7f, 0xfb, 0xd6, 0xc4, 0xc3, 0xdd, 0xe8, 0xb1,
+ 0x60, 0xfc, 0xc6, 0xb9, 0x0d, 0x6a, 0x33, 0x78, 0xc6, 0xc1, 0xbf, 0x86, 0x2c, 0x50, 0xcc,
+ 0x9a, 0x70, 0x8e, 0x7b, 0xec, 0xab, 0x95, 0xac, 0x53, 0xa0, 0x4b, 0x07, 0x88, 0xaf, 0x42,
+ 0xed, 0x19, 0x8d, 0xf6, 0x32, 0x17, 0x48, 0x47, 0x1d, 0x41, 0x6f, 0xfe, 0x2e, 0xa7, 0x8f,
+ 0x4b, 0xa0, 0x51, 0xf3, 0xbf, 0x02, 0x0a, 0x48, 0x58, 0xf7, 0xa1, 0x6d, 0xea, 0xa5, 0x13,
+ 0x5a, 0x5b, 0xea, 0x0c, 0x9e, 0x52, 0x4f, 0x9e, 0xb9, 0x71, 0x7f, 0x23, 0x83, 0xda, 0x1b,
+ 0x86, 0x9a, 0x41, 0x29, 0xda, 0x70, 0xe7, 0x64, 0xa1, 0x7b, 0xd5, 0x0a, 0x22, 0x0d, 0x5c,
+ 0x40, 0xc4, 0x81, 0x07, 0x25, 0x35, 0x4a, 0x1c, 0x10, 0xdb, 0x45, 0x0a, 0xff, 0x36, 0xd4,
+ 0xe0, 0xeb, 0x5f, 0x68, 0xd6, 0x67, 0xc6, 0xd0, 0x8b, 0x76, 0x1a, 0x7d, 0x59, 0x42, 0xa1,
+ 0xcb, 0x96, 0x4d, 0x84, 0x09, 0x9a, 0x3d, 0xe0, 0x52, 0x85, 0x6e, 0x48, 0x90, 0x85, 0x2a,
+ 0x63, 0xb2, 0x69, 0xd2, 0x00, 0x43, 0x31, 0x37, 0xb3, 0x52, 0xaf, 0x62, 0xfa, 0xc1, 0xe0,
+ 0x03, 0xfb, 0x62, 0xaa, 0x88, 0xc9, 0xb2, 0x2c, 0xd5, 0xa8, 0xf5, 0xa5, 0x4c, 0x12, 0x59,
+ 0x4e, 0x06, 0x5e, 0x9b, 0x15, 0x66, 0x11, 0xb2, 0x27, 0x92, 0xdc, 0x98, 0x59, 0xde, 0xdf,
+ 0xfa, 0x9a, 0x32, 0x2e, 0xc0, 0x5d, 0x3c, 0x33, 0x41, 0x6d, 0xaf, 0xb2, 0x25, 0x23, 0x14,
+ 0xa5, 0x7b, 0xc7, 0x9b, 0x68, 0xf3, 0xda, 0xeb, 0xe3, 0xa9, 0xe2, 0x6f, 0x0e, 0x1d, 0x1c,
+ 0xba, 0x55, 0xb6, 0x34, 0x6a, 0x93, 0x1f, 0x1f, 0xb8, 0x34, 0xc8, 0x84, 0x08, 0xb1, 0x6b,
+ 0x6a, 0x28, 0x74, 0x74, 0xe5, 0xeb, 0x75, 0xe9, 0x7c, 0xd8, 0xba, 0xd8, 0x42, 0xa5, 0xee,
+ 0x1f, 0x80, 0xd9, 0x96, 0xb2, 0x2e, 0xe7, 0xbf, 0xba, 0xeb, 0xd1, 0x69, 0xbb, 0x8f, 0xfd,
+ 0x5a, 0x63, 0x8f, 0x39, 0x7f, 0xdf, 0x1d, 0x37, 0xd2, 0x18, 0x35, 0x9d, 0xb6, 0xcc, 0xe4,
+ 0x27, 0x81, 0x89, 0x38, 0x38, 0x68, 0x33, 0xe7, 0x78, 0xd8, 0x76, 0xf5, 0xee, 0xd0, 0x4a,
+ 0x07, 0x69, 0x19, 0x7a, 0xad, 0x18, 0xb1, 0x94, 0x61, 0x45, 0x53, 0xa2, 0x48, 0xda, 0x96,
+ 0x4a, 0xf9, 0xee, 0x94, 0x2a, 0x1f, 0x6e, 0x18, 0x3c, 0x92, 0x46, 0xd1, 0x1a, 0x28, 0x18,
+ 0x32, 0x1f, 0x3a, 0x45, 0xbe, 0x04, 0x35, 0x92, 0xe5, 0xa3, 0xcb, 0xb5, 0x2e, 0x32, 0x43,
+ 0xac, 0x65, 0x17, 0x89, 0x99, 0x15, 0x03, 0x9e, 0xb1, 0x23, 0x2f, 0xed, 0x76, 0x4d, 0xd8,
+ 0xac, 0x21, 0x40, 0xc4, 0x99, 0x4e, 0x65, 0x71, 0x2c, 0xb3, 0x45, 0xab, 0xfb, 0xe7, 0x72,
+ 0x39, 0x56, 0x30, 0x6d, 0xfb, 0x74, 0xeb, 0x99, 0xf3, 0xcd, 0x57, 0x5c, 0x78, 0x75, 0xe9,
+ 0x8d, 0xc3, 0xa2, 0xfb, 0x5d, 0xe0, 0x90, 0xc5, 0x55, 0xad, 0x91, 0x53, 0x4e, 0x9e, 0xbd,
+ 0x8c, 0x49, 0xa4, 0xa4, 0x69, 0x10, 0x0c, 0xc5, 0x76, 0xe9, 0x25, 0x86, 0x8d, 0x66, 0x23,
+ 0xa8, 0xdb, 0x5c, 0xe8, 0xd9, 0x30, 0xe1, 0x15, 0x7b, 0xc0, 0x99, 0x0f, 0x03, 0xec, 0xaa,
+ 0x12, 0xef, 0xce, 0xd4, 0xea, 0x55, 0x5c, 0x08, 0x86, 0xf4, 0xf4, 0xb0, 0x83, 0x42, 0x95,
+ 0x37, 0xb6, 0x38, 0xe0, 0x2b, 0x54, 0x89, 0xbd, 0x4e, 0x20, 0x9d, 0x3f, 0xc3, 0x4b, 0xb7,
+ 0xec, 0xfa, 0x5a, 0x14, 0x03, 0xcb, 0x64, 0xc8, 0x34, 0x4a, 0x4b, 0x6e, 0xf8, 0x6e, 0x56,
+ 0xf6, 0xdd, 0x5f, 0xa1, 0x24, 0xe2, 0xd4, 0xd0, 0x82, 0x64, 0x1f, 0x8e, 0x9b, 0xfa, 0xb4,
+ 0xcb, 0xdb, 0x0a, 0xe8, 0x15, 0xfc, 0x15, 0xab, 0x4b, 0x18, 0xbf, 0xd4, 0x42, 0x14, 0x48,
+ 0x82, 0x85, 0xdd, 0xeb, 0x49, 0x1b, 0x0b, 0x0b, 0x05, 0xe9, 0xb4, 0xa1, 0x33, 0x0a, 0x5d,
+ 0x0e, 0x6c, 0x4b, 0xc0, 0xd6, 0x6c, 0x7c, 0xfb, 0x69, 0x0b, 0x53, 0x19, 0xe4, 0xf3, 0x35,
+ 0xfc, 0xbe, 0xa1, 0x34, 0x02, 0x09, 0x4f, 0x74, 0x86, 0x92, 0xcd, 0x5d, 0x1a, 0xc1, 0x27,
+ 0x0c, 0xf2, 0xc5, 0xcf, 0xdd, 0x23, 0x93, 0x02, 0xbd, 0x41, 0x5e, 0x42, 0xf0, 0xa0, 0x9d,
+ 0x0c, 0x72, 0xc8, 0xec, 0x32, 0x0a, 0x8a, 0xfd, 0x3d, 0x5a, 0x41, 0x27, 0x0c, 0x88, 0x59,
+ 0xad, 0x94, 0x2e, 0xef, 0x5d, 0x8f, 0xc7, 0xdf, 0x66, 0xe4, 0xdd, 0x56, 0x6c, 0x7b, 0xca,
+ 0x55, 0x81, 0xae, 0xae, 0x5c, 0x1b, 0x1a, 0xab, 0xae, 0x99, 0x8d, 0xcc, 0x42, 0x97, 0x59,
+ 0xf4, 0x14, 0x3f, 0x75, 0xc6, 0xd1, 0x88, 0xba, 0xaa, 0x84, 0x4a, 0xd0, 0x34, 0x08, 0x3b,
+ 0x7d, 0xdb, 0x15, 0x06, 0xb0, 0x5c, 0xbd, 0x40, 0xf5, 0xa8, 0xec, 0xae, 0x36, 0x40, 0xdd,
+ 0x90, 0x1c, 0x3e, 0x0d, 0x7e, 0x73, 0xc7, 0xc2, 0xc5, 0x6a, 0xff, 0x52, 0x05, 0x7f, 0xbe,
+ 0xd0, 0x92, 0xfd, 0xb3, 0x6f, 0xff, 0x5d, 0xb7, 0x97, 0x64, 0x73, 0x7b, 0xca, 0xd1, 0x98,
+ 0x24, 0x6b, 0x0b, 0x01, 0x68, 0xdd, 0x27, 0x85, 0x85, 0xb5, 0x83, 0xc1, 0xe0, 0x50, 0x64,
+ 0xc7, 0xaf, 0xf1, 0xc6, 0x4d, 0xb1, 0xef, 0xc9, 0xb4, 0x0a, 0x6d, 0x65, 0xf3, 0x47, 0xcc,
+ 0xa3, 0x02, 0x21, 0x0c, 0xbe, 0x22, 0x29, 0x05, 0xcf, 0x5f, 0xe8, 0x94, 0x6c, 0xe5, 0xdc,
+ 0xc4, 0xdf, 0xbe, 0x3e, 0xa8, 0xb4, 0x18, 0xb0, 0x99, 0xb8, 0x6f, 0xff, 0x5d, 0xb9, 0xfd,
+ 0x3b, 0x5d, 0x16, 0xbf, 0x3e, 0xd8, 0xb3, 0xd8, 0x08, 0x34, 0xf6, 0x47, 0x35, 0x5b, 0x72,
+ 0x1a, 0x33, 0xad, 0x52, 0x5d, 0xb8, 0xd0, 0x77, 0xc6, 0xab, 0xba, 0x55, 0x09, 0x5f, 0x02,
+ 0xf8, 0xd4, 0x5f, 0x53, 0x06, 0x91, 0xcd, 0x74, 0x42, 0xae, 0x54, 0x91, 0x81, 0x62, 0x13,
+ 0x6f, 0xd8, 0xa9, 0x77, 0xc3, 0x6c, 0xcb, 0xf1, 0x29, 0x5a, 0xcc, 0xda, 0x35, 0xbd, 0x52,
+ 0x23, 0xbe, 0x59, 0xeb, 0x12, 0x6d, 0xb7, 0x53, 0xee, 0xfc, 0xb4, 0x1b, 0x13, 0x5e, 0xba,
+ 0x16, 0x7c, 0xc5, 0xf3, 0xe3, 0x6d, 0x07, 0x78, 0xf5, 0x2b, 0x21, 0x05, 0x88, 0x4c, 0xc0,
+ 0xa1, 0xe3, 0x36, 0x10, 0xf8, 0x1b, 0xd8, 0x17, 0xfb, 0x6a, 0x4e, 0xd8, 0xb3, 0x47, 0x2d,
+ 0x99, 0xbd, 0xbb, 0x5d, 0x37, 0x7d, 0xba, 0xf1, 0xe1, 0x7c, 0xc0, 0xc5, 0x54, 0x62, 0x7f,
+ 0xcf, 0x5a, 0x4a, 0x93, 0xcc, 0xf1, 0x1b, 0x34, 0xc8, 0xa6, 0x05, 0x4c, 0x55, 0x8b, 0x54,
+ 0x84, 0xd5, 0x77, 0xeb, 0xc0, 0x6d, 0x3a, 0x29, 0xbd, 0x75, 0x61, 0x09, 0x9a, 0x2c, 0xbb,
+ 0xf7, 0x18, 0x79, 0x34, 0x90, 0x24, 0xa5, 0x81, 0x70, 0x87, 0xc5, 0x02, 0x7c, 0xba, 0xd4,
+ 0x5e, 0x14, 0x8e, 0xe4, 0xed, 0xa2, 0x61, 0x6a, 0xb9, 0x6e, 0xb5, 0x4a, 0xb9, 0x01, 0x46,
+ 0xf4, 0xcf, 0xbc, 0x09, 0x2f, 0x27, 0x4b, 0xbd, 0x86, 0x7a, 0x10, 0xe1, 0xd4, 0xc8, 0xd9,
+ 0x20, 0x8d, 0x8a, 0x63, 0x00, 0x63, 0x44, 0xeb, 0x54, 0x0b, 0x75, 0x49, 0x10, 0xa2, 0xa7,
+ 0xad, 0xb9, 0xd1, 0x01, 0x80, 0x63, 0x25, 0xc8, 0x12, 0xa6, 0xce, 0x1e, 0xbe, 0xfe, 0x7e,
+ 0x5f, 0x3c, 0xdb, 0x34, 0xea, 0x37, 0xec, 0x3b, 0xd5, 0x28, 0xd2, 0x07, 0x8c, 0x9a, 0xb6,
+ 0xee, 0x5e, 0x3e, 0xdf, 0x1d, 0x99, 0xb0, 0xe2, 0x46, 0xef, 0x5c, 0x1b, 0xb4, 0xea, 0x56,
+ 0x2e, 0xde, 0x1f, 0x9d, 0xb8, 0xd3, 0x24, 0xab, 0xd4, 0x2a, 0xd6, 0x2e, 0xde, 0x1f, 0x9d,
+ 0xb8, 0xf2, 0x66, 0x2f, 0xbd, 0xf8, 0x72, 0x66, 0x4e, 0x1e, 0x9f, 0x9d, 0xb8, 0xf2, 0x47,
+ 0x0c, 0x9a, 0xb6, 0xee, 0x3f, 0xfc, 0x7a, 0x57, 0x0d, 0x79, 0x70, 0x62, 0x27, 0xad, 0xb9,
+ 0xd1, 0x01, 0x61, 0x40, 0x02, 0x67, 0x2d, 0xd8, 0x32, 0xe6, 0x2f, 0xdc, 0x3a, 0xd7, 0x2c,
+ 0xbb, 0xf4, 0x4b, 0xf5, 0x49, 0xf1, 0x60, 0x23, 0xc4, 0x0a, 0x77, 0x4d, 0xf9, 0x51, 0x01,
+ 0x80, 0x63, 0x25, 0xa9, 0xb1, 0xe0, 0x42, 0xe7, 0x4c, 0x1a, 0x97, 0xac, 0xbb, 0xf4, 0x6a,
+ 0x37, 0xcd, 0x18, 0xb2, 0xe6, 0x2f, 0xdc, 0x1b, 0x95, 0xa8, 0xd2, 0x07, 0x6d, 0x58, 0x32,
+ 0xe6, 0x4e, 0x1e, 0x9f, 0xbc, 0xfa, 0x57, 0x0d, 0x79, 0x51, 0x20, 0xc2, 0x06, 0x6f, 0x5c,
+ 0x1b, 0x95, 0xa8, 0xb3, 0xc5, 0xe9, 0x31, 0xe0, 0x23, 0xc4, 0x0a, 0x77, 0x4d, 0x18, 0x93,
+ 0x85, 0x69, 0x31, 0xc1, 0xe1, 0x21, 0xc0, 0xe3, 0x44, 0x0a, 0x77, 0x6c, 0x5a, 0x17, 0x8d,
+ 0x98, 0x93, 0xa4, 0xab, 0xd4, 0x2a, 0xb7, 0xec, 0x5a, 0x17, 0xac, 0xbb, 0xf4, 0x4b, 0x14,
+ 0xaa, 0xb7, 0xec, 0x3b, 0xd5, 0x28, 0xb3, 0xc5, 0xe9, 0x31, 0xc1, 0x00, 0x82, 0x67, 0x4c,
+ 0xfb, 0x55, 0x28, 0xd2, 0x26, 0xaf, 0xbd, 0xd9, 0x11, 0x81, 0x61, 0x21, 0xa1, 0xa1, 0xc0,
+ 0x02, 0x86, 0x6f, 0x5c, 0x1b, 0xb4, 0xcb, 0x14, 0x8b, 0x94, 0xaa, 0xd6, 0x2e, 0xbf, 0xdd,
+ 0x19, 0xb0, 0xe2, 0x46, 0x0e, 0x7f, 0x7c, 0x5b, 0x15, 0x89, 0x90, 0x83, 0x84, 0x6b, 0x54,
+ 0x0b, 0x75, 0x68, 0x52, 0x07, 0x6d, 0x58, 0x32, 0xc7, 0xed, 0x58, 0x32, 0xc7, 0xed, 0x58,
+ 0x32, 0xe6, 0x4e, 0xff, 0x7c, 0x7a, 0x76, 0x6e, 0x3f, 0xdd, 0x38, 0xd3, 0x05, 0x88, 0x92,
+ 0xa6, 0xaf, 0xdc, 0x1b, 0xb4, 0xcb, 0xf5, 0x68, 0x52, 0x07, 0x8c, 0x7b, 0x55, 0x09, 0x90,
+ 0x83, 0x84, 0x6b, 0x54, 0x2a, 0xb7, 0xec, 0x3b, 0xd5, 0x09, 0x90, 0xa2, 0xc6, 0x0e, 0x7f,
+ 0x7c, 0x7a, 0x57, 0x0d, 0x98, 0xb2, 0xc7, 0xed, 0x58, 0x32, 0xc7, 0x0c, 0x7b, 0x74, 0x4b,
+ 0x14, 0x8b, 0x94, 0xaa, 0xb7, 0xcd, 0x18, 0x93, 0xa4, 0xca, 0x16, 0xae, 0xbf, 0xdd, 0x19,
+ 0xb0, 0xe2, 0x46, 0x0e, 0x7f, 0x5d, 0x19, 0x91, 0x81, 0x80, 0x63, 0x44, 0xeb, 0x35, 0xc9,
+ 0x10, 0x83, 0x65, 0x48, 0x12, 0xa6, 0xce, 0x1e, 0x9f, 0xbc, 0xdb, 0x15, 0x89, 0x71, 0x60,
+ 0x23, 0xc4, 0xeb, 0x54, 0x2a, 0xb7, 0xec, 0x5a, 0x36, 0xcf, 0x81, 0x10, 0xac, 0x74
+};
// clang-format off
diff --git a/drivers/serial.h b/drivers/serial.h
index d9c2a69e96..0cfdbd9959 100644
--- a/drivers/serial.h
+++ b/drivers/serial.h
@@ -26,21 +26,4 @@ void soft_serial_initiator_init(void);
// target is interrupt accept side
void soft_serial_target_init(void);
-// initiator result
-#define TRANSACTION_END 0
-#define TRANSACTION_NO_RESPONSE 0x1
-#define TRANSACTION_DATA_ERROR 0x2
-#define TRANSACTION_TYPE_ERROR 0x4
-int soft_serial_transaction(int sstd_index);
-
-// target status
-// *SSTD_t.status has
-// initiator:
-// TRANSACTION_END
-// or TRANSACTION_NO_RESPONSE
-// or TRANSACTION_DATA_ERROR
-// target:
-// TRANSACTION_DATA_ERROR
-// or TRANSACTION_ACCEPTED
-#define TRANSACTION_ACCEPTED 0x8
-int soft_serial_get_and_clean_status(int sstd_index);
+bool soft_serial_transaction(int sstd_index);
diff --git a/drivers/usb2422.c b/drivers/usb2422.c
index 62b919093b..8ee54b24ee 100644
--- a/drivers/usb2422.c
+++ b/drivers/usb2422.c
@@ -352,7 +352,7 @@ void USB2422_init() {
setPinInput(USB2422_ACTIVE_PIN);
#endif
- i2c_init(); // IC2 clk must be high at USB2422 reset release time to signal SMB configuration
+ i2c_init(); // IC2 clk must be high at USB2422 reset release time to signal SMB configuration
}
void USB2422_configure() {
@@ -363,14 +363,14 @@ void USB2422_configure() {
// configure Usb2422 registers
config.VID.reg = USB2422_VENDOR_ID;
config.PID.reg = USB2422_PRODUCT_ID;
- config.DID.reg = USB2422_DEVICE_VER; // BCD format, eg 01.01
- config.CFG1.bit.SELF_BUS_PWR = 1; // self powered for now
- config.CFG1.bit.HS_DISABLE = 1; // full or high speed
+ config.DID.reg = USB2422_DEVICE_VER; // BCD format, eg 01.01
+ config.CFG1.bit.SELF_BUS_PWR = 1; // self powered for now
+ config.CFG1.bit.HS_DISABLE = 1; // full or high speed
// config.CFG2.bit.COMPOUND = 0; // compound device
- config.CFG3.bit.STRING_EN = 1; // strings enabled
+ config.CFG3.bit.STRING_EN = 1; // strings enabled
// config.NRD.bit.PORT2_NR = 0; // MCU is non-removable
- config.MAXPB.reg = 20; // 0mA
- config.HCMCB.reg = 20; // 0mA
+ config.MAXPB.reg = 20; // 0mA
+ config.HCMCB.reg = 20; // 0mA
config.MFRSL.reg = sizeof(USB2422_MANUFACTURER);
config.PRDSL.reg = sizeof(USB2422_PRODUCT);
config.SERSL.reg = sizeof(SERNAME);
diff --git a/drivers/ws2812.h b/drivers/ws2812.h
index 945b3d0728..5985b5340c 100644
--- a/drivers/ws2812.h
+++ b/drivers/ws2812.h
@@ -33,19 +33,19 @@
#endif
#ifndef WS2812_T1H
-# define WS2812_T1H 900 // Width of a 1 bit in ns
+# define WS2812_T1H 900 // Width of a 1 bit in ns
#endif
#ifndef WS2812_T1L
-# define WS2812_T1L (WS2812_TIMING - WS2812_T1H) // Width of a 1 bit in ns
+# define WS2812_T1L (WS2812_TIMING - WS2812_T1H) // Width of a 1 bit in ns
#endif
#ifndef WS2812_T0H
-# define WS2812_T0H 350 // Width of a 0 bit in ns
+# define WS2812_T0H 350 // Width of a 0 bit in ns
#endif
#ifndef WS2812_T0L
-# define WS2812_T0L (WS2812_TIMING - WS2812_T0H) // Width of a 0 bit in ns
+# define WS2812_T0L (WS2812_TIMING - WS2812_T0H) // Width of a 0 bit in ns
#endif
/*