Skip to content

Commit

Permalink
firmware: pinout v2: move sunk to uart1, move sunm to pio uart
Browse files Browse the repository at this point in the history
  • Loading branch information
delan committed Feb 18, 2024
1 parent 7085b44 commit 391833f
Show file tree
Hide file tree
Showing 13 changed files with 310 additions and 68 deletions.
34 changes: 34 additions & 0 deletions debug1.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
diff --git a/.pio/libdeps/pico/Adafruit TinyUSB Library/src/Adafruit_TinyUSB.h b/.pio/libdeps/pico/Adafruit TinyUSB Library/src/Adafruit_TinyUSB.h
index 1d0808c..25b5f95 100644
--- a/.pio/libdeps/pico/Adafruit TinyUSB Library/src/Adafruit_TinyUSB.h
+++ b/.pio/libdeps/pico/Adafruit TinyUSB Library/src/Adafruit_TinyUSB.h
@@ -25,6 +25,9 @@
#ifndef ADAFRUIT_TINYUSB_H_
#define ADAFRUIT_TINYUSB_H_

+#include <Arduino.h>
+extern HardwareSerial *TinyUSB_Serial_Debug;
+
// Error message for Core that must select TinyUSB via menu
#if !defined(USE_TINYUSB) && ( defined(ARDUINO_ARCH_SAMD) || \
(defined(ARDUINO_ARCH_RP2040) && !defined(ARDUINO_ARCH_MBED)) )
diff --git a/.pio/libdeps/pico/Adafruit TinyUSB Library/src/arduino/ports/rp2040/Adafruit_TinyUSB_rp2040.cpp b/.pio/libdeps/pico/Adafruit TinyUSB Library/src/arduino/ports/rp2040/Adafruit_TinyUSB_rp2040.cpp
index 8af08a4..b0449dd 100644
--- a/.pio/libdeps/pico/Adafruit TinyUSB Library/src/arduino/ports/rp2040/Adafruit_TinyUSB_rp2040.cpp
+++ b/.pio/libdeps/pico/Adafruit TinyUSB Library/src/arduino/ports/rp2040/Adafruit_TinyUSB_rp2040.cpp
@@ -141,13 +141,14 @@ void TinyUSB_Device_Task(void) {

// Debug log with Serial1
#if CFG_TUSB_DEBUG
+HardwareSerial *TinyUSB_Serial_Debug = nullptr;
int serial1_printf(const char *__restrict format, ...) {
char buf[256];
int len;
va_list ap;
va_start(ap, format);
len = vsnprintf(buf, sizeof(buf), format, ap);
- Serial1.write(buf);
+ if (TinyUSB_Serial_Debug) TinyUSB_Serial_Debug->write(buf);
va_end(ap);
return len;
}
28 changes: 28 additions & 0 deletions debug2.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
diff --git a/cores/rp2040/debug_internal.h b/cores/rp2040/debug_internal.h
index 81026fb..e8b206f 100644
--- a/cores/rp2040/debug_internal.h
+++ b/cores/rp2040/debug_internal.h
@@ -20,6 +20,9 @@

#pragma once

+typedef int SerialPrintf(const char *format, ...) __attribute__ ((format (printf, 1, 2)));
+extern SerialPrintf *DEBUG_RP2040_PRINTF;
+
#if !defined(DEBUG_RP2040_PORT)
#define DEBUGV(...) do { } while(0)
#define DEBUGCORE(...) do { } while(0)
diff --git a/cores/rp2040/main.cpp b/cores/rp2040/main.cpp
index fb1ed21..a8e98f9 100644
--- a/cores/rp2040/main.cpp
+++ b/cores/rp2040/main.cpp
@@ -24,6 +24,9 @@
#include <pico/multicore.h>
#include <reent.h>

+static int dummyDebugPrintf(const char *, ...) { return -1; }
+SerialPrintf *DEBUG_RP2040_PRINTF = dummyDebugPrintf;
+
RP2040 rp2040;
extern "C" {
volatile bool __otherCoreIdled = false;
5 changes: 4 additions & 1 deletion doc/firmware.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,12 @@ firmware
## how to build the firmware

1. fix the -DCFG_TUSB_CONFIG_FILE in platformio.ini for your absolute path
2. apply patches to <.pio/libdeps/pico/Adafruit TinyUSB Library/src/host/usbh.c> (version 2.0.1)
2. apply patches to [Adafruit TinyUSB Library](https://github.com/adafruit/Adafruit_TinyUSB_Arduino) (version 2.0.1)
1. `git apply tinyusb1.patch`[tinyusb1.patch](tinyusb1.patch) fixes a race condition in enumeration when two devices are connected at the same time (hathach/tinyusb#1786, upstreamed in 2.0.2 as hathach/tinyusb#1960)
2. `git apply tinyusb2.patch`[tinyusb2.patch](tinyusb2.patch) improves compatibility with Microsoft Wired Keyboard 600 (045E:0750) and 400 (045E:0752) when CFG_TUSB_DEBUG < 2 by adding a delay in tuh_control_xfer
3. `git apply debug1.patch`[debug1.patch](debug1.patch)
3. apply patches to [framework-arduinopico](https://github.com/earlephilhower/arduino-pico) (version 1.30101.0)
1. `git -C ~/.platformio/packages/framework-arduinopico apply $PWD/debug2.patch`[debug2.patch](debug2.patch)

### linux users

Expand Down
2 changes: 1 addition & 1 deletion platformio.ini
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ lib_deps =
https://github.com/adafruit/Adafruit_SSD1306.git#2.5.7
https://github.com/adafruit/Adafruit_TinyUSB_Arduino.git#2.0.1
https://github.com/sekigon-gonnoc/Pico-PIO-USB.git#0.5.2
build_flags = -DUSB3SUN_VERSION=\"1.5\" -DUSE_TINYUSB -DCFG_TUSB_CONFIG_FILE=\"/home/delan/code/usb3sun/tusb_config.h\" ; -DCFG_TUSB_DEBUG=3
build_flags = -DUSB3SUN_VERSION=\"1.5\" -DUSE_TINYUSB -DCFG_TUSB_CONFIG_FILE=\"/home/delan/code/usb3sun/tusb_config.h\" ; -DCFG_TUSB_DEBUG=3 -DDEBUG_RP2040_WIRE -DDEBUG_RP2040_SPI -DDEBUG_RP2040_CORE
board_build.f_cpu = 120000000L
board_build.filesystem_size = 64k
; build_type = debug
Expand Down
75 changes: 50 additions & 25 deletions src/config.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,13 @@
#define DISPLAY_ROTATION 0 // 0|1|2|3 where 0 means GND pin is bottom left
// FIXME no longer used
#define SUNM_BAUD 9600 // 1200|2400|4800|9600 where higher is smoother and more responsive

#define DEBUG_LOGGING // allow any logging to Serial or Serial1
#define DEBUG_LOGGING // allow any logging
#define DEBUG_OVER_CDC // log to Serial (USB CDC); excludes TinyUSB debugging
#define DEBUG_OVER_UART // log to Serial1 (UART0); includes TinyUSB debugging
// (ignored in pinout v1 when SUNK_ENABLE is defined)
#define DEBUG_UART_BAUD 115200 // only 115200 works with stock picoprobe firmware

// #define DEBUG_TIMINGS // log time spent on critical operations
// #define BUZZER_VERBOSE // log buzzer state changes for debugging
// #define SUNK_VERBOSE // log keyboard tx for debugging
Expand All @@ -16,49 +22,68 @@
#define USB1_DP 4 // GP# number for USB root port 1 D+
#define USB1_DM (USB_DP+1) // GP# number for USB root port 1 D- (always D+ GP# + 1)
#define BUZZER_PIN 28 // GP# number for positive of passive piezo buzzer
#define PINOUT_V2_PIN 7 // GP# number for detecting pinout v2 (rev A4+)

// the following must be GP# numbers valid for...
#define DEBUG_UART_TX 0 // ...UART0 TX: connect to picoprobe GP5
#define DEBUG_UART_RX 1 // ...UART0 RX: connect to picoprobe GP4
#define DISPLAY_SCL 17 // ...I2C0 SCL: SCL pin of SSD1306
#define DISPLAY_SDA 16 // ...I2C0 SDA: SDA pin of SSD1306

// pinout v1/v2 config
// the following must be GP# numbers valid for...
// pin 1: 0 V (purple)
// pin 2: 0 V (brown)
// pin 3: +5 Vdc (blue)
#define SUN_MTX 8 // ...UART1 TX: pin 4: mouse tx (gray)
#define SUN_MRX 9 // ...UART1 RX: n/c: mouse rx
#define SUN_KRX 13 // ...UART0 RX: pin 5: keyboard rx (red)
#define SUN_KTX 12 // ...UART0 TX: pin 6: keyboard tx (green)
#define POWER_KEY 15 // ...any: pin 7: power key (yellow)
// pin 8: +5 Vdc (orange)
// pin 1: 0 V (purple)
// pin 2: 0 V (brown)
// pin 3: +5 Vdc (blue)
// n/c: mouse rx
#define SUN_MRX_V1 9 // ...UART1 RX (required by SerialUART api)
// pin 4: mouse tx (gray)
#define SUN_MTX_V1 8 // ...UART1 TX
#define SUN_MTX_V2 6 // ...any
// pin 5: keyboard rx (red)
#define SUN_KRX_V1 13 // ...UART0 RX
#define SUN_KRX_V2 9 // ...UART1 RX
// pin 6: keyboard tx (green)
#define SUN_KTX_V1 12 // ...UART0 TX
#define SUN_KTX_V2 8 // ...UART1 TX
// pin 7: power key (yellow)
#define POWER_KEY 15 // ...any
// pin 8: +5 Vdc (orange)
#define DEBUG_UART Serial1 // UART0
#define SUNK_UART_V1 Serial1 // UART0
#define SUNK_UART_V2 Serial2 // UART1
#define SUNM_UART_V1 Serial2 // UART1

// send output over Serial1 instead of Serial (disables Sun keyboard interface)
// #define PICOPROBE_ENABLE
#if !defined(PICOPROBE_ENABLE)
#define SUNK_ENABLE
#endif
#define PICOPROBE_BAUD 115200 // values other than 9600 may require PuTTY/minicom
#define SUNM_ENABLE

// FIXME broken in pinout v2
// fake Sun host for loopback testing (disables Sun mouse interface)
// #define FAKE_SUN_ENABLE
#if !defined(FAKE_SUN_ENABLE)
#define SUNM_ENABLE
#endif

// FIXME broken in pinout v2
// the following must be GP# numbers valid for...
#define FAKE_SUN_KRX 8 // ...UART1 TX: connect to SUN_KRX
#define FAKE_SUN_KTX 9 // ...UART1 RX: connect to SUN_KTX
#define PICOPROBE_TX 0 // ...UART0 TX: connect to picoprobe GP5
#define PICOPROBE_RX 1 // ...UART0 RX: connect to picoprobe GP4

#ifdef PICOPROBE_ENABLE
#define Sprint(...) (Serial1.print(__VA_ARGS__), Serial1.flush())
#define Sprintln(...) (Serial1.println(__VA_ARGS__), Serial1.flush())
#define Sprintf(...) (Serial1.printf(__VA_ARGS__), Serial1.flush())
#elif defined(DEBUG_LOGGING)
#define Sprint(...) (Serial.print(__VA_ARGS__), Serial.flush())
#define Sprintln(...) (Serial.println(__VA_ARGS__), Serial.flush())
#define Sprintf(...) (Serial.printf(__VA_ARGS__), Serial.flush())
#if defined(DEBUG_LOGGING)
#define DEBUG_PRINT_FLUSH(port, method, ...) (port.method(__VA_ARGS__), port.flush())
#if defined(DEBUG_OVER_CDC) && defined(DEBUG_OVER_UART)
#define Sprint(...) do { DEBUG_PRINT_FLUSH(Serial, print, __VA_ARGS__); if (pinout.canDebugOverUart) DEBUG_PRINT_FLUSH(DEBUG_UART, print, __VA_ARGS__); } while (0)
#define Sprintln(...) do { DEBUG_PRINT_FLUSH(Serial, println, __VA_ARGS__); if (pinout.canDebugOverUart) DEBUG_PRINT_FLUSH(DEBUG_UART, println, __VA_ARGS__); } while (0)
#define Sprintf(...) do { DEBUG_PRINT_FLUSH(Serial, printf, __VA_ARGS__); if (pinout.canDebugOverUart) DEBUG_PRINT_FLUSH(DEBUG_UART, printf, __VA_ARGS__); } while (0)
#elif defined(DEBUG_OVER_CDC)
#define Sprint(...) DEBUG_PRINT_FLUSH(Serial, print, __VA_ARGS__)
#define Sprintln(...) DEBUG_PRINT_FLUSH(Serial, println, __VA_ARGS__)
#define Sprintf(...) DEBUG_PRINT_FLUSH(Serial, printf, __VA_ARGS__)
#elif defined(DEBUG_OVER_UART)
#define Sprint(...) do { if (pinout.canDebugOverUart) DEBUG_PRINT_FLUSH(DEBUG_UART, print, __VA_ARGS__); } while (0)
#define Sprintln(...) do { if (pinout.canDebugOverUart) DEBUG_PRINT_FLUSH(DEBUG_UART, println, __VA_ARGS__); } while (0)
#define Sprintf(...) do { if (pinout.canDebugOverUart) DEBUG_PRINT_FLUSH(DEBUG_UART, printf, __VA_ARGS__); } while (0)
#endif
#else
#define Sprint(...) do {} while (0)
#define Sprintln(...) do {} while (0)
Expand Down
69 changes: 38 additions & 31 deletions src/main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include <Arduino.h>
#include <Wire.h>
#include <CoreMutex.h>
#include <SerialPIO.h>

extern "C" {
#include <pio_usb.h>
Expand All @@ -18,6 +19,7 @@ extern "C" {
#include "buzzer.h"
#include "display.h"
#include "menu.h"
#include "pinout.h"
#include "settings.h"
#include "state.h"
#include "sunk.h"
Expand Down Expand Up @@ -51,6 +53,7 @@ struct {

std::atomic<bool> wait = true;

Pinout pinout;
State state;
Buzzer buzzer;
Settings settings;
Expand Down Expand Up @@ -149,6 +152,14 @@ void setup() {
pinMode(LED_BUILTIN, OUTPUT);
digitalWrite(LED_BUILTIN, HIGH);

// check for pinout v2 (active high)
pinMode(PINOUT_V2_PIN, INPUT_PULLDOWN);
if (digitalRead(PINOUT_V2_PIN) == HIGH) {
pinout.v2();
} else {
pinout.v1();
}

// needs to be done manually when using FreeRTOS and/or TinyUSB
Serial.begin(115200);

Expand All @@ -168,31 +179,14 @@ void setup() {

Settings::begin();
settings.readAll();
pinout.beginSun();

#if defined(PICOPROBE_ENABLE)
Serial1.end(); // needed under CFG_TUSB_DEBUG
Serial1.setPinout(PICOPROBE_TX, PICOPROBE_RX);
Serial1.setFIFOSize(4096);
Serial1.begin(115200, SERIAL_8N1);
#elif defined(SUNK_ENABLE)
// gpio invert must be set *after* setPinout/begin
Serial1.setPinout(SUN_KTX, SUN_KRX);
Serial1.begin(1200, SERIAL_8N1);
gpio_set_outover(SUN_KTX, GPIO_OVERRIDE_INVERT);
gpio_set_inover(SUN_KRX, GPIO_OVERRIDE_INVERT);
#endif
#if defined(FAKE_SUN_ENABLE)
// gpio invert must be set *after* setPinout/begin
Serial2.setPinout(FAKE_SUN_KRX, FAKE_SUN_KTX);
Serial2.begin(1200, SERIAL_8N1);
gpio_set_outover(FAKE_SUN_KRX, GPIO_OVERRIDE_INVERT);
gpio_set_inover(FAKE_SUN_KTX, GPIO_OVERRIDE_INVERT);
#elif defined(SUNM_ENABLE)
// gpio invert must be set *after* setPinout/begin
Serial2.setPinout(SUN_MTX, SUN_MRX);
Serial2.begin(settings.mouseBaudReal(), SERIAL_8N1);
gpio_set_outover(SUN_MTX, GPIO_OVERRIDE_INVERT);
gpio_set_inover(SUN_MRX, GPIO_OVERRIDE_INVERT);
#endif

for (int i = 0; i < splash_height; i += 2) {
Expand Down Expand Up @@ -266,18 +260,18 @@ void loop() {
}

#ifdef SUNK_ENABLE
void serialEvent1() {
while (Serial1.available() > 0) {
uint8_t command = Serial1.read();
void sunkEvent() {
while (pinout.sunk->available() > 0) {
uint8_t command = pinout.sunk->read();
Sprintf("sun keyboard: rx command %02Xh\n", command);
switch (command) {
case SUNK_RESET:
// self test fail:
// Serial.write(0x7E);
// Serial.write(0x01);
Serial1.write(SUNK_RESET_RESPONSE);
Serial1.write(0x04);
Serial1.write(0x7F); // TODO optional make code
// pinout.sunk->write(0x7E);
// pinout.sunk->write(0x01);
pinout.sunk->write(SUNK_RESET_RESPONSE);
pinout.sunk->write(0x04);
pinout.sunk->write(0x7F); // TODO optional make code
break;
case SUNK_BELL_ON:
state.bell = true;
Expand All @@ -294,8 +288,8 @@ void serialEvent1() {
state.clickEnabled = false;
break;
case SUNK_LED: {
while (Serial1.peek() == -1) delay(1);
uint8_t status = Serial1.read();
while (pinout.sunk->peek() == -1) delay(1);
uint8_t status = pinout.sunk->read();
Sprintf("sun keyboard: led status %02Xh\n", status);
state.num = status & 1 << 0;
state.compose = status & 1 << 1;
Expand All @@ -307,14 +301,26 @@ void serialEvent1() {
rp2040.fifo.push_nb((uint32_t)Message::UHID_LED_FROM_STATE);
} break;
case SUNK_LAYOUT: {
Serial1.write(SUNK_LAYOUT_RESPONSE);
pinout.sunk->write(SUNK_LAYOUT_RESPONSE);
// UNITED STATES (TODO alternate layouts)
uint8_t layout = 0b00000000;
Serial1.write(&layout, 1);
pinout.sunk->write(&layout, 1);
} break;
}
}
}

void serialEvent1() {
#if defined(SUNK_ENABLE)
sunkEvent();
#endif
}

void serialEvent2() {
#if defined(SUNK_ENABLE)
sunkEvent();
#endif
}
#endif

#ifdef FAKE_SUN_ENABLE
Expand Down Expand Up @@ -358,6 +364,7 @@ void setup1() {

pio_usb_configuration_t pio_cfg = PIO_USB_DEFAULT_CONFIG;
pio_cfg.pin_dp = USB0_DP;
pio_cfg.sm_tx = 1;

// tuh_configure -> pico pio hcd_configure -> memcpy to static global
USBHost.configure_pio_usb(1, &pio_cfg);
Expand Down Expand Up @@ -598,7 +605,7 @@ void tuh_hid_report_received_cb(uint8_t dev_addr, uint8_t instance, uint8_t cons
(uint8_t) mreport->x, (uint8_t) -mreport->y, 0, 0,
};
#ifdef SUNM_ENABLE
size_t len = Serial2.write(result, sizeof(result) / sizeof(*result));
size_t len = pinout.sunm->write(result, sizeof(result) / sizeof(*result));
#ifdef SUNM_VERBOSE
Sprintf("sun mouse: tx %02Xh %02Xh %02Xh %02Xh %02Xh = %zu\n",
result[0], result[1], result[2], result[3], result[4], len);
Expand Down
11 changes: 3 additions & 8 deletions src/menu.cc
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
#include "bindings.h"
#include "display.h"
#include "hostid.h"
#include "pinout.h"
#include "settings.h"
#include "state.h"
#include "sunk.h"
Expand Down Expand Up @@ -158,10 +159,7 @@ void MenuView::sel(uint8_t usbkSelector) {
case (size_t)MenuItem::MouseBaud:
++settings.mouseBaud();
settings.write(settings.mouseBaud_field);
Serial2.end();
Serial2.begin(settings.mouseBaudReal(), SERIAL_8N1);
gpio_set_outover(SUN_MTX, GPIO_OVERRIDE_INVERT);
gpio_set_outover(SUN_MRX, GPIO_OVERRIDE_INVERT);
pinout.restartSunm();
break;
}
break;
Expand All @@ -181,10 +179,7 @@ void MenuView::sel(uint8_t usbkSelector) {
case (size_t)MenuItem::MouseBaud:
--settings.mouseBaud();
settings.write(settings.mouseBaud_field);
Serial2.end();
Serial2.begin(settings.mouseBaudReal(), SERIAL_8N1);
gpio_set_outover(SUN_MTX, GPIO_OVERRIDE_INVERT);
gpio_set_outover(SUN_MRX, GPIO_OVERRIDE_INVERT);
pinout.restartSunm();
break;
}
break;
Expand Down
1 change: 1 addition & 0 deletions src/panic.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
#define USB3SUN_PANIC_H

#include "config.h"
#include "pinout.h"

#include <Arduino.h>

Expand Down
Loading

0 comments on commit 391833f

Please sign in to comment.