Skip to content

Commit

Permalink
Ch341 (meshtastic#5474)
Browse files Browse the repository at this point in the history
* Very hacky first attempt at usermod ech341

* Fixes and debug printfs

* Move to library version of libpinedio-usb

* Add spidev: ch341 option in meshtasticd config.yaml

* Only check settingsStrings on native

* Use new CH341 code

* Bump ch341 lib

* Cleanup USBHal

* Add ch341 config.d files

* Remove ch341quirk

* Bump to most recent spi-userspace driver

* Add handling for ch341 serial, pid, and vid

* Minor fixes from pio check

* Trunk

* Add include for musl compliance

* Point to upstream libch341
  • Loading branch information
jp-bennett authored Dec 20, 2024
1 parent 658459a commit 960626e
Show file tree
Hide file tree
Showing 10 changed files with 327 additions and 105 deletions.
3 changes: 2 additions & 1 deletion arch/portduino/portduino.ini
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ lib_deps =
${radiolib_base.lib_deps}
rweather/Crypto@^0.4.0
https://github.com/lovyan03/LovyanGFX.git#1401c28a47646fe00538d487adcb2eb3c72de805
https://github.com/pine64/libch341-spi-userspace#8695637adeabf5abf5601d8e82cb0ba19ce9ec46

build_flags =
${arduino_base.build_flags}
Expand All @@ -36,4 +37,4 @@ build_flags =
-lstdc++fs
-lbluetooth
-lgpiod
-lyaml-cpp
-lyaml-cpp
9 changes: 0 additions & 9 deletions bin/config-dist.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,6 @@ Lora:
# IRQ: 17
# Reset: 22

# Module: sx1262 # pinedio
# CS: 0
# IRQ: 10
# Busy: 11
# DIO2_AS_RF_SWITCH: true
# spidev: spidev0.1

# Module: RF95 # Adafruit RFM9x
# Reset: 25
# CS: 7
Expand Down Expand Up @@ -50,8 +43,6 @@ Lora:
# TXen: x # TX and RX enable pins
# RXen: x

# ch341_quirk: true # Uncomment this to use the chunked SPI transfer that seems to fix the ch341

# spiSpeed: 2000000

### Set gpio chip to use in /dev/. Defaults to 0.
Expand Down
11 changes: 11 additions & 0 deletions bin/config.d/lora-meshstick-1262.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
Lora:
Module: sx1262
CS: 0
IRQ: 6
Reset: 2
Busy: 4
spidev: ch341
DIO3_TCXO_VOLTAGE: true
# USB_Serialnum: 12345678
USB_PID: 0x5512
USB_VID: 0x1A86
5 changes: 5 additions & 0 deletions bin/config.d/lora-pinedio-usb-sx1262.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
Lora:
Module: sx1262
CS: 0
IRQ: 10
spidev: ch341
31 changes: 20 additions & 11 deletions src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,6 +90,7 @@ NRF52Bluetooth *nrf52Bluetooth = nullptr;
#include "linux/LinuxHardwareI2C.h"
#include "mesh/raspihttp/PiWebServer.h"
#include "platform/portduino/PortduinoGlue.h"
#include "platform/portduino/USBHal.h"
#include <fstream>
#include <iostream>
#include <string>
Expand Down Expand Up @@ -213,6 +214,9 @@ static OSThread *powerFSMthread;
static OSThread *ambientLightingThread;

RadioInterface *rIf = NULL;
#ifdef ARCH_PORTDUINO
RadioLibHal *RadioLibHAL = NULL;
#endif

/**
* Some platforms (nrf52) might provide an alterate version that suppresses calling delay from sleep.
Expand Down Expand Up @@ -241,7 +245,7 @@ void setup()
// GPIO10 manages all peripheral power supplies
// Turn on peripheral power immediately after MUC starts.
// If some boards are turned on late, ESP32 will reset due to low voltage.
// ESP32-C3(Keyboard) , MAX98357A(Audio Power Amplifier) ,
// ESP32-C3(Keyboard) , MAX98357A(Audio Power Amplifier) ,
// TF Card , Display backlight(AW9364DNR) , AN48841B(Trackball) , ES7210(Decoder)
pinMode(KB_POWERON, OUTPUT);
digitalWrite(KB_POWERON, HIGH);
Expand Down Expand Up @@ -420,7 +424,6 @@ void setup()
digitalWrite(AQ_SET_PIN, HIGH);
#endif


// Currently only the tbeam has a PMU
// PMU initialization needs to be placed before i2c scanning
power = new Power();
Expand Down Expand Up @@ -706,12 +709,16 @@ void setup()
pinMode(LORA_CS, OUTPUT);
digitalWrite(LORA_CS, HIGH);
SPI1.begin(false);
#else // HW_SPI1_DEVICE
#else // HW_SPI1_DEVICE
SPI.setSCK(LORA_SCK);
SPI.setTX(LORA_MOSI);
SPI.setRX(LORA_MISO);
SPI.begin(false);
#endif // HW_SPI1_DEVICE
#endif // HW_SPI1_DEVICE
#elif ARCH_PORTDUINO
if (settingsStrings[spidev] != "ch341") {
SPI.begin();
}
#elif !defined(ARCH_ESP32) // ARCH_RP2040
SPI.begin();
#else
Expand Down Expand Up @@ -817,8 +824,11 @@ void setup()
if (settingsMap[use_sx1262]) {
if (!rIf) {
LOG_DEBUG("Activate sx1262 radio on SPI port %s", settingsStrings[spidev].c_str());
LockingArduinoHal *RadioLibHAL =
new LockingArduinoHal(SPI, spiSettings, (settingsMap[ch341Quirk] ? settingsMap[busy] : RADIOLIB_NC));
if (settingsStrings[spidev] == "ch341") {
RadioLibHAL = ch341Hal;
} else {
RadioLibHAL = new LockingArduinoHal(SPI, spiSettings);
}
rIf = new SX1262Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset],
settingsMap[busy]);
if (!rIf->init()) {
Expand All @@ -832,8 +842,7 @@ void setup()
} else if (settingsMap[use_rf95]) {
if (!rIf) {
LOG_DEBUG("Activate rf95 radio on SPI port %s", settingsStrings[spidev].c_str());
LockingArduinoHal *RadioLibHAL =
new LockingArduinoHal(SPI, spiSettings, (settingsMap[ch341Quirk] ? settingsMap[busy] : RADIOLIB_NC));
RadioLibHAL = new LockingArduinoHal(SPI, spiSettings);
rIf = new RF95Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset],
settingsMap[busy]);
if (!rIf->init()) {
Expand All @@ -848,7 +857,7 @@ void setup()
} else if (settingsMap[use_sx1280]) {
if (!rIf) {
LOG_DEBUG("Activate sx1280 radio on SPI port %s", settingsStrings[spidev].c_str());
LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(SPI, spiSettings);
RadioLibHAL = new LockingArduinoHal(SPI, spiSettings);
rIf = new SX1280Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset],
settingsMap[busy]);
if (!rIf->init()) {
Expand Down Expand Up @@ -908,7 +917,7 @@ void setup()
} else if (settingsMap[use_sx1268]) {
if (!rIf) {
LOG_DEBUG("Activate sx1268 radio on SPI port %s", settingsStrings[spidev].c_str());
LockingArduinoHal *RadioLibHAL = new LockingArduinoHal(SPI, spiSettings);
RadioLibHAL = new LockingArduinoHal(SPI, spiSettings);
rIf = new SX1268Interface((LockingArduinoHal *)RadioLibHAL, settingsMap[cs], settingsMap[irq], settingsMap[reset],
settingsMap[busy]);
if (!rIf->init()) {
Expand Down Expand Up @@ -1265,4 +1274,4 @@ void loop()
mainDelay.delay(delayMsec);
}
}
#endif
#endif
26 changes: 1 addition & 25 deletions src/mesh/RadioLibInterface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,31 +31,7 @@ void LockingArduinoHal::spiEndTransaction()
#if ARCH_PORTDUINO
void LockingArduinoHal::spiTransfer(uint8_t *out, size_t len, uint8_t *in)
{
if (busy == RADIOLIB_NC) {
spi->transfer(out, in, len);
} else {
uint16_t offset = 0;

while (len) {
uint8_t block_size = (len < 20 ? len : 20);
spi->transfer((out != NULL ? out + offset : NULL), (in != NULL ? in + offset : NULL), block_size);
if (block_size == len)
return;

// ensure GPIO is low

uint32_t start = millis();
while (digitalRead(busy)) {
if (!Throttle::isWithinTimespanMs(start, 2000)) {
LOG_ERROR("GPIO mid-transfer timeout, is it connected?");
return;
}
}

offset += block_size;
len -= block_size;
}
}
spi->transfer(out, in, len);
}
#endif

Expand Down
9 changes: 1 addition & 8 deletions src/mesh/RadioLibInterface.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,18 +22,11 @@
class LockingArduinoHal : public ArduinoHal
{
public:
LockingArduinoHal(SPIClass &spi, SPISettings spiSettings, RADIOLIB_PIN_TYPE _busy = RADIOLIB_NC)
: ArduinoHal(spi, spiSettings)
{
#if ARCH_PORTDUINO
busy = _busy;
#endif
};
LockingArduinoHal(SPIClass &spi, SPISettings spiSettings) : ArduinoHal(spi, spiSettings){};

void spiBeginTransaction() override;
void spiEndTransaction() override;
#if ARCH_PORTDUINO
RADIOLIB_PIN_TYPE busy;
void spiTransfer(uint8_t *out, size_t len, uint8_t *in) override;

#endif
Expand Down
135 changes: 86 additions & 49 deletions src/platform/portduino/PortduinoGlue.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,12 @@
#include <sys/ioctl.h>
#include <unistd.h>

#include "platform/portduino/USBHal.h"

std::map<configNames, int> settingsMap;
std::map<configNames, std::string> settingsStrings;
std::ofstream traceFile;
Ch341Hal *ch341Hal = nullptr;
char *configPath = nullptr;
char *optionMac = nullptr;

Expand Down Expand Up @@ -104,7 +107,6 @@ void getMacAddr(uint8_t *dmac)
struct hci_dev_info di;
di.dev_id = 0;
bdaddr_t bdaddr;
char addr[18];
int btsock;
btsock = socket(AF_BLUETOOTH, SOCK_RAW, 1);
if (btsock < 0) { // If anything fails, just return with the default value
Expand Down Expand Up @@ -201,8 +203,36 @@ void portduinoSetup()
}
}
}

// if we're using a usermode driver, we need to initialize it here, to get a serial number back for mac address
uint8_t dmac[6] = {0};
if (settingsStrings[spidev] == "ch341") {
ch341Hal = new Ch341Hal(0);
if (settingsStrings[lora_usb_serial_num] != "") {
ch341Hal->serial = settingsStrings[lora_usb_serial_num];
}
ch341Hal->vid = settingsMap[lora_usb_vid];
ch341Hal->pid = settingsMap[lora_usb_pid];
ch341Hal->init();
if (!ch341Hal->isInit()) {
std::cout << "Could not initialize CH341 device!" << std::endl;
exit(EXIT_FAILURE);
}
char serial[9] = {0};
ch341Hal->getSerialString(serial, 8);
std::cout << "Serial " << serial << std::endl;
if (strlen(serial) == 8 && settingsStrings[mac_address].length() < 12) {
uint8_t hash[32] = {0};
memcpy(hash, serial, 8);
crypto->hash(hash, 8);
dmac[0] = (hash[0] << 4) | 2;
dmac[1] = hash[1];
dmac[2] = hash[2];
dmac[3] = hash[3];
dmac[4] = hash[4];
dmac[5] = hash[5];
}
}

getMacAddr(dmac);
if (dmac[0] == 0 && dmac[1] == 0 && dmac[2] == 0 && dmac[3] == 0 && dmac[4] == 0 && dmac[5] == 0) {
std::cout << "*** Blank MAC Address not allowed!" << std::endl;
Expand All @@ -225,47 +255,11 @@ void portduinoSetup()
// Need to bind all the configured GPIO pins so they're not simulated
// TODO: Can we do this in the for loop above?
// TODO: If one of these fails, we should log and terminate
if (settingsMap.count(cs) > 0 && settingsMap[cs] != RADIOLIB_NC) {
if (initGPIOPin(settingsMap[cs], gpioChipName) != ERRNO_OK) {
settingsMap[cs] = RADIOLIB_NC;
}
}
if (settingsMap.count(irq) > 0 && settingsMap[irq] != RADIOLIB_NC) {
if (initGPIOPin(settingsMap[irq], gpioChipName) != ERRNO_OK) {
settingsMap[irq] = RADIOLIB_NC;
}
}
if (settingsMap.count(busy) > 0 && settingsMap[busy] != RADIOLIB_NC) {
if (initGPIOPin(settingsMap[busy], gpioChipName) != ERRNO_OK) {
settingsMap[busy] = RADIOLIB_NC;
}
}
if (settingsMap.count(reset) > 0 && settingsMap[reset] != RADIOLIB_NC) {
if (initGPIOPin(settingsMap[reset], gpioChipName) != ERRNO_OK) {
settingsMap[reset] = RADIOLIB_NC;
}
}
if (settingsMap.count(sx126x_ant_sw) > 0 && settingsMap[sx126x_ant_sw] != RADIOLIB_NC) {
if (initGPIOPin(settingsMap[sx126x_ant_sw], gpioChipName) != ERRNO_OK) {
settingsMap[sx126x_ant_sw] = RADIOLIB_NC;
}
}
if (settingsMap.count(user) > 0 && settingsMap[user] != RADIOLIB_NC) {
if (initGPIOPin(settingsMap[user], gpioChipName) != ERRNO_OK) {
settingsMap[user] = RADIOLIB_NC;
}
}
if (settingsMap.count(rxen) > 0 && settingsMap[rxen] != RADIOLIB_NC) {
if (initGPIOPin(settingsMap[rxen], gpioChipName) != ERRNO_OK) {
settingsMap[rxen] = RADIOLIB_NC;
}
}
if (settingsMap.count(txen) > 0 && settingsMap[txen] != RADIOLIB_NC) {
if (initGPIOPin(settingsMap[txen], gpioChipName) != ERRNO_OK) {
settingsMap[txen] = RADIOLIB_NC;
}
}

if (settingsMap[displayPanel] != no_screen) {
if (settingsMap[displayCS] > 0)
initGPIOPin(settingsMap[displayCS], gpioChipName);
Expand All @@ -283,7 +277,43 @@ void portduinoSetup()
initGPIOPin(settingsMap[touchscreenIRQ], gpioChipName);
}

if (settingsStrings[spidev] != "") {
// Only initialize the radio pins when dealing with real, kernel controlled SPI hardware
if (settingsStrings[spidev] != "" && settingsStrings[spidev] != "ch341") {
if (settingsMap.count(cs) > 0 && settingsMap[cs] != RADIOLIB_NC) {
if (initGPIOPin(settingsMap[cs], gpioChipName) != ERRNO_OK) {
settingsMap[cs] = RADIOLIB_NC;
}
}
if (settingsMap.count(irq) > 0 && settingsMap[irq] != RADIOLIB_NC) {
if (initGPIOPin(settingsMap[irq], gpioChipName) != ERRNO_OK) {
settingsMap[irq] = RADIOLIB_NC;
}
}
if (settingsMap.count(busy) > 0 && settingsMap[busy] != RADIOLIB_NC) {
if (initGPIOPin(settingsMap[busy], gpioChipName) != ERRNO_OK) {
settingsMap[busy] = RADIOLIB_NC;
}
}
if (settingsMap.count(reset) > 0 && settingsMap[reset] != RADIOLIB_NC) {
if (initGPIOPin(settingsMap[reset], gpioChipName) != ERRNO_OK) {
settingsMap[reset] = RADIOLIB_NC;
}
}
if (settingsMap.count(sx126x_ant_sw) > 0 && settingsMap[sx126x_ant_sw] != RADIOLIB_NC) {
if (initGPIOPin(settingsMap[sx126x_ant_sw], gpioChipName) != ERRNO_OK) {
settingsMap[sx126x_ant_sw] = RADIOLIB_NC;
}
}
if (settingsMap.count(rxen) > 0 && settingsMap[rxen] != RADIOLIB_NC) {
if (initGPIOPin(settingsMap[rxen], gpioChipName) != ERRNO_OK) {
settingsMap[rxen] = RADIOLIB_NC;
}
}
if (settingsMap.count(txen) > 0 && settingsMap[txen] != RADIOLIB_NC) {
if (initGPIOPin(settingsMap[txen], gpioChipName) != ERRNO_OK) {
settingsMap[txen] = RADIOLIB_NC;
}
}
SPI.begin(settingsStrings[spidev].c_str());
}
if (settingsStrings[traceFilename] != "") {
Expand Down Expand Up @@ -378,17 +408,24 @@ bool loadConfig(const char *configPath)
settingsMap[rxen] = yamlConfig["Lora"]["RXen"].as<int>(RADIOLIB_NC);
settingsMap[sx126x_ant_sw] = yamlConfig["Lora"]["SX126X_ANT_SW"].as<int>(RADIOLIB_NC);
settingsMap[gpiochip] = yamlConfig["Lora"]["gpiochip"].as<int>(0);
settingsMap[ch341Quirk] = yamlConfig["Lora"]["ch341_quirk"].as<bool>(false);
settingsMap[spiSpeed] = yamlConfig["Lora"]["spiSpeed"].as<int>(2000000);

settingsStrings[spidev] = "/dev/" + yamlConfig["Lora"]["spidev"].as<std::string>("spidev0.0");
if (settingsStrings[spidev].length() == 14) {
int x = settingsStrings[spidev].at(11) - '0';
int y = settingsStrings[spidev].at(13) - '0';
if (x >= 0 && x < 10 && y >= 0 && y < 10) {
settingsMap[spidev] = x + y << 4;
settingsMap[displayspidev] = settingsMap[spidev];
settingsMap[touchscreenspidev] = settingsMap[spidev];
settingsStrings[lora_usb_serial_num] = yamlConfig["Lora"]["USB_Serialnum"].as<std::string>("");
settingsMap[lora_usb_pid] = yamlConfig["Lora"]["USB_PID"].as<int>(0x5512);
settingsMap[lora_usb_vid] = yamlConfig["Lora"]["USB_VID"].as<int>(0x1A86);

settingsStrings[spidev] = yamlConfig["Lora"]["spidev"].as<std::string>("spidev0.0");
if (settingsStrings[spidev] != "ch341") {
settingsStrings[spidev] = "/dev/" + settingsStrings[spidev];
if (settingsStrings[spidev].length() == 14) {
int x = settingsStrings[spidev].at(11) - '0';
int y = settingsStrings[spidev].at(13) - '0';
// Pretty sure this is always true
if (x >= 0 && x < 10 && y >= 0 && y < 10) {
// I believe this bit of weirdness is specifically for the new GUI
settingsMap[spidev] = x + y << 4;
settingsMap[displayspidev] = settingsMap[spidev];
settingsMap[touchscreenspidev] = settingsMap[spidev];
}
}
}
}
Expand Down
Loading

0 comments on commit 960626e

Please sign in to comment.