Holy shit, routable USB-Serial is working

This commit is contained in:
Kevin Santo Cappuccio 2023-12-07 20:43:55 -08:00
parent aa8e8f7127
commit 4094c3b688
19 changed files with 503 additions and 46709 deletions

View File

@ -40,6 +40,7 @@ def openSerial():
serialconnected = 0
portSelected = 0
foundports = []
print("\n")
@ -52,21 +53,28 @@ def openSerial():
print("{}: {} [{}]".format(i, port, desc))
if desc == "Jumperless":
autodetected = i
foundports.append(ports[autodetected-1][0])
selection = -1
sortedports = sorted(foundports,key = lambda x:x[-1])
#print(sortedports)
if autodetected != -1:
#if autodetected != -1:
if False:
selection = autodetected
print("\n\nAutodetected Jumperless at", end=" ")
print(ports[int(selection) - 1].device)
portName = ports[int(selection) - 1].device
print(sortedports[0])
#portName = ports[int(selection) - 1].device
portName = sortedports[0]
portSelected = True
serialconnected = 1
else:
selection = input(
"\n\nSelect the port connected to your Jumperless ('r' to rescan)\n\n")
"\n\nSelect the port connected to your Jumperless ('r' to rescan)\n\n(Choose the lower numbered port, the other is routable USB-Serial)\n\n")
if selection.isdigit() == True and int(selection) <= i:
portName = ports[int(selection) - 1].device
@ -692,7 +700,13 @@ while True:
conn1 = "108"
elif conn1.endswith('5'):
conn1 = "109"
elif conn1.endswith('6'):
conn1 = "116"
elif conn1.endswith('7'):
conn1 = "117"
elif conn1.endswith('D'):
conn1 = "114"
if conn1.startswith("bb1:") == True:
periodIndex = conn1.find('.')
conn1 = conn1[4:periodIndex]
@ -761,6 +775,12 @@ while True:
conn2 = "108"
elif conn2.endswith('5'):
conn2 = "109"
elif conn2.endswith('6'):
conn2 = "116"
elif conn2.endswith('7'):
conn2 = "117"
elif conn2.endswith('D'):
conn2 = "114"
if conn2.startswith("bb1:") == True:
periodIndex = conn2.find('.')

Binary file not shown.

View File

@ -7,7 +7,8 @@
"usb_vid": "0x2e8a",
"usb_pid": "0x000a",
"usb_manufacturer": "Architeuthis Flux",
"usb_product": "Jumperless"
"usb_product": "Jumperless"
}
},
"core": "arduino",

View File

@ -1,31 +0,0 @@
{
"version": 1,
"author": "Anonymous maker",
"editor": "wokwi",
"parts": [
{ "type": "wokwi-breadboard-half", "id": "bb1", "top": -694.2, "left": -141.2, "attrs": {} },
{ "type": "wokwi-arduino-nano", "id": "nano", "top": -791, "left": -62.59, "attrs": {} },
{ "type": "wokwi-led", "id": "led1", "top": -666, "left": -92.2, "attrs": { "color": "red" } },
{
"type": "wokwi-resistor",
"id": "r1",
"top": -629.65,
"left": 19.2,
"attrs": { "value": "1000" }
},
{ "type": "wokwi-gnd", "id": "gnd1", "top": -671.42, "left": 210.03, "attrs": {} },
{ "type": "wokwi-vcc", "id": "vcc1", "top": -757.34, "left": 201.2, "attrs": {} }
],
"connections": [
[ "vcc1:VCC", "bb1:tp.25", "red", [ "v18.96", "h-49.2" ] ],
[ "led1:A", "bb1:6t.c", "", [ "$bb" ] ],
[ "led1:C", "bb1:5t.c", "", [ "$bb" ] ],
[ "r1:1", "bb1:15t.c", "", [ "$bb" ] ],
[ "r1:2", "bb1:21t.c", "", [ "$bb" ] ],
[ "bb1:15t.e", "bb1:6t.e", "black", [ "v11.61", "h-84.29" ] ],
[ "bb1:21t.a", "bb1:tn.18", "black", [ "v0" ] ],
[ "bb1:5t.d", "bb1:tp.2", "red", [ "h-18.93", "v-67.5" ] ],
[ "gnd1:GND", "bb1:tn.25", "black", [ "v0" ] ]
],
"dependencies": {}
}

View File

@ -0,0 +1,142 @@
/*
The MIT License (MIT)
Copyright (c) 2018, hathach for Adafruit
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to
deal in the Software without restriction, including without limitation the
rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
sell copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
IN THE SOFTWARE.
*/
#ifndef _TUSB_CONFIG_RP2040_H_
#define _TUSB_CONFIG_RP2040_H_
#ifdef __cplusplus
extern "C" {
#endif
//--------------------------------------------------------------------
// COMMON CONFIGURATION
//--------------------------------------------------------------------
#define CFG_TUSB_RHPORT0_MODE OPT_MODE_DEVICE
// Enable device stack
#define CFG_TUD_ENABLED 1
// Enable host stack with pio-usb if Pico-PIO-USB library is available
#if __has_include("pio_usb.h")
#define CFG_TUH_ENABLED 1
#define CFG_TUH_RPI_PIO_USB 1
#endif
#ifndef CFG_TUSB_MCU
#define CFG_TUSB_MCU OPT_MCU_RP2040
#endif
#define CFG_TUSB_OS OPT_OS_PICO
#ifndef CFG_TUSB_DEBUG
#define CFG_TUSB_DEBUG 0
#endif
// For selectively disable device log (when > CFG_TUSB_DEBUG)
// #define CFG_TUD_LOG_LEVEL 3
// #define CFG_TUH_LOG_LEVEL 3
#define CFG_TUSB_MEM_SECTION
#define CFG_TUSB_MEM_ALIGN TU_ATTR_ALIGNED(4)
//--------------------------------------------------------------------
// Device Configuration
//--------------------------------------------------------------------
#define CFG_TUD_ENDOINT0_SIZE 64
#define CFG_TUD_CDC 2
#define CFG_TUD_MSC 1
#define CFG_TUD_HID 1
#define CFG_TUD_MIDI 1
#define CFG_TUD_VENDOR 1
// CDC FIFO size of TX and RX
#define CFG_TUD_CDC_RX_BUFSIZE 256
#define CFG_TUD_CDC_TX_BUFSIZE 256
// MSC Buffer size of Device Mass storage
#define CFG_TUD_MSC_EP_BUFSIZE 512
// HID buffer size Should be sufficient to hold ID (if any) + Data
#define CFG_TUD_HID_EP_BUFSIZE 64
// MIDI FIFO size of TX and RX
#define CFG_TUD_MIDI_RX_BUFSIZE 128
#define CFG_TUD_MIDI_TX_BUFSIZE 128
// Vendor FIFO size of TX and RX
#define CFG_TUD_VENDOR_RX_BUFSIZE 64
#define CFG_TUD_VENDOR_TX_BUFSIZE 64
//--------------------------------------------------------------------
// Host Configuration
//--------------------------------------------------------------------
// Size of buffer to hold descriptors and other data used for enumeration
#define CFG_TUH_ENUMERATION_BUFSIZE 256
// Number of hub devices
#define CFG_TUH_HUB 1
// max device support (excluding hub device): 1 hub typically has 4 ports
#define CFG_TUH_DEVICE_MAX (3 * CFG_TUH_HUB + 1)
// Enable tuh_edpt_xfer() API
// #define CFG_TUH_API_EDPT_XFER 1
// Number of mass storage
#define CFG_TUH_MSC 1
// Number of HIDs
// typical keyboard + mouse device can have 3,4 HID interfaces
#define CFG_TUH_HID (3 * CFG_TUH_DEVICE_MAX)
// Number of CDC interfaces
// FTDI and CP210x are not part of CDC class, only to re-use CDC driver API
#define CFG_TUH_CDC 2
#define CFG_TUH_CDC_FTDI 1
#define CFG_TUH_CDC_CP210X 1
// RX & TX fifo size
#define CFG_TUH_CDC_RX_BUFSIZE 128
#define CFG_TUH_CDC_TX_BUFSIZE 128
// Set Line Control state on enumeration/mounted:
// DTR ( bit 0), RTS (bit 1)
#define CFG_TUH_CDC_LINE_CONTROL_ON_ENUM 0x03
// Set Line Coding on enumeration/mounted, value for cdc_line_coding_t
// bit rate = 115200, 1 stop bit, no parity, 8 bit data width
// This need Pico-PIO-USB at least 0.5.1
#define CFG_TUH_CDC_LINE_CODING_ON_ENUM \
{ 115200, CDC_LINE_CONDING_STOP_BITS_1, CDC_LINE_CODING_PARITY_NONE, 8 }
#ifdef __cplusplus
}
#endif
#endif /* _TUSB_CONFIG_RP2040_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -15,6 +15,12 @@ board_build.core = earlephilhower
board_build.filesystem_size = 0.5m
extra_scripts = pre:scripts/find_Jumperless_upload.py, post:scripts/extra_script.py
monitor_speed = 256000
build_flags =
-DUSE_TINYUSB
-DCFG_TUSB_CONFIG_FILE=\"custom_tusb_config.h\"
-Iinclude/
[env:pico]
board = pico

View File

@ -20,6 +20,8 @@ def find_jumperless_port_monitor(source, target, env):
if desc == "Jumperless":
autodetected = i
print("Autodetected jumperless port: " + ports[autodetected][0])
i = i + 1
if autodetected != -1:

View File

@ -8,22 +8,31 @@ def find_jumperless_port_upload(source, target, env):
autodetected = -1
ports = serial.tools.list_ports.comports()
i = 0
foundports = []
for port, desc, hwid in ports:
print("{}: {} [{}]".format(i, port, desc))
if desc == "Jumperless":
autodetected = i
#print("Autodetected jumperless port: " + ports[autodetected][0]+ ' ' + ports[autodetected][1])
foundports.append(ports[autodetected][0])
#break
i = i + 1
if autodetected != -1:
selection = autodetected
env.Replace(MONITOR_PORT=ports[selection][0])
env.Replace(UPLOAD_PORT=ports[selection][0])
#(env, "monitor_port", ports[selection][0])
# ConfigEnvOption(env, "upload_port", ports[selection][0])
print("Autodetected jumperless port: " + ports[selection][0])
#print(foundports[0] + ' ' + foundports[1])
sortedports = sorted(foundports,key = lambda x:x[-1])
print(sortedports)
selection = autodetected
# env.Replace(MONITOR_PORT=ports[selection][0])
env.Replace(UPLOAD_PORT=sortedports[0])
print("Autodetected jumperless port: " + sortedports[0])

View File

@ -1,67 +1,38 @@
#include "ArduinoStuff.h"
#include "MatrixStateRP2040.h"
#include "NetsToChipConnections.h"
#include "LEDs.h"
#include "JumperlessDefinesRP2040.h"
#include "ArduinoStuff.h"
#include <Arduino.h>
//#include <SoftwareSerial.h>
// #include "JumperlessDefinesRP2040.h"
// #include <Arduino.h>
// #include <SoftwareSerial.h>
//SoftwareSerial ardSerial(1, 0);
// SoftwareSerial ardSerial(1, 0);
// SerialPIO ardSerial(1, 0);
//SerialPIO ardSerial(1, 0);
// SerialPIO routableUART(16,17,32);
// SoftwareSerial routableUART(16,17);
void initArduino (void) //if the UART is set up, the Arduino won't flash from it's own USB port
void initArduino(void) // if the UART is set up, the Arduino won't flash from it's own USB port
{
//Serial1.setRX(1);
//Serial1.setTX(0);
//pinMode (1, OUTPUT);
//pinMode (0, INPUT);
Serial1.begin(115200);
Serial1.println("hello from arduino");
Serial1.setRX(17);
Serial1.setTX(16);
Serial1.begin(115200);
delay(1);
}
void arduinoPrint (void)
void arduinoPrint(void)
{
if (Serial1.available())
{
Serial1.read();
Serial.write( Serial1.read());
}
//Serial1.println("fuck");
}
void uploadArduino (void)
void uploadArduino(void)
{
while (!Serial.available());
while (Serial.available())
{
Serial1.write(Serial.read());
}
}

View File

@ -5,6 +5,11 @@
void initArduino(void);
void arduinoPrint(void);

View File

@ -179,7 +179,7 @@ void resetArduino(void)
path[lastPath].y[1] = 0;
sendPath(lastPath, 1);
delay(100);
delay(3);
sendPath(lastPath, 0);
}
void sendAllPaths(void) // should we sort them by chip? for now, no

View File

@ -1,3 +1,8 @@
#ifndef JUMPERLESSDEFINESRP2040_H
#define JUMPERLESSDEFINESRP2040_H
#define PIOSTUFF 1 //comment these out to remove them
#define EEPROMSTUFF 1
#define FSSTUFF 1
@ -118,15 +123,15 @@
#define t30 30
#define b1 31
#define b2 32
#define b3 33
#define b4 34
#define b5 35
#define b6 36
#define b7 37
#define b8 38
#define b9 39
#define b1 31
#define b2 32
#define b3 33
#define b4 34
#define b5 35
#define b6 36
#define b7 37
#define b8 38
#define b9 39
#define b10 40
#define b11 41
#define b12 42
@ -196,8 +201,12 @@
#define ADC3_8V 113
#define RP_GPIO_0 114
#define RP_UART_RX 116
#define RP_UART_TX 117
#define RP_UART_TX 116
#define RP_UART_RX 117
#define EMPTY_NET 127
#define EMPTY_NET 127
#endif

View File

@ -59,15 +59,15 @@ void initLEDs(void)
EEPROM.write(DEBUG_LEDSADDRESS, debugLEDs);
pinMode(LED_PIN, OUTPUT);
delay(30);
delay(1);
leds.begin(); // INITIALIZE NeoPixel strip object (REQUIRED)
delay(30);
delay(1);
leds.show();
delay(40);
delay(2);
// leds.setBrightness(100);
delay(20);
delay(2);
EEPROM.commit();
delay(100);
delay(20);
}
char LEDbrightnessMenu(void)
@ -660,7 +660,7 @@ void lightUpNet(int netNumber, int node, int onOff, int brightness2, int hueShif
int colorCorrection = 0;
int pcbHueShift = 0;
if (net[netNumber].nodes[1] != 0 && net[netNumber].nodes[1] < 121)
if (net[netNumber].nodes[1] != 0 && net[netNumber].nodes[1] <= NANO_A7)
{
for (int j = 0; j < MAX_NODES; j++)
@ -669,7 +669,7 @@ void lightUpNet(int netNumber, int node, int onOff, int brightness2, int hueShif
{
break;
}
if (net[netNumber].nodes[j] < 121)
if (net[netNumber].nodes[j] <= NANO_A7)
{
if (net[netNumber].nodes[j] == node || node == -1)
{
@ -753,6 +753,16 @@ void lightUpNet(int netNumber, int node, int onOff, int brightness2, int hueShif
}
leds.setPixelColor(nodesToPixelMap[net[netNumber].nodes[j]], color);
if (debugLEDs)
{
Serial.print("net: ");
Serial.print(netNumber);
Serial.print(" node: ");
Serial.print(net[netNumber].nodes[j]);
Serial.print(" mapped to LED:");
Serial.println(nodesToPixelMap[net[netNumber].nodes[j]]);
}
}
else
{
@ -1451,7 +1461,7 @@ struct rgbColor unpackRgb(uint32_t color)
}
void clearLEDs(void)
{
for (int i = 0; i <= LED_COUNT; i++)
for (int i = 0; i <= 254; i++)
{ // For each pixel in strip...
leds.setPixelColor(i, 0); // Set pixel's color (in RAM)

View File

@ -113,7 +113,7 @@ struct chipStatus ch[12] = {
{11,'L',
{-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1}, // x status
{-1,-1,-1,-1,-1,-1,-1,-1}, //y status
{CURRENT_SENSE_MINUS, CURRENT_SENSE_PLUS, ADC0_5V, ADC1_5V, ADC2_5V, ADC3_8V, DAC1_8V, DAC0_5V, t1, t30, b1, b30, RP_UART_RX, RP_UART_TX, SUPPLY_5V, RP_GPIO_0},
{CURRENT_SENSE_MINUS, CURRENT_SENSE_PLUS, ADC0_5V, ADC1_5V, ADC2_5V, ADC3_8V, DAC1_8V, DAC0_5V, t1, t30, b1, b30, RP_UART_TX, RP_UART_RX, SUPPLY_5V, RP_GPIO_0},
{CHIP_A,CHIP_B,CHIP_C,CHIP_D,CHIP_E,CHIP_F,CHIP_G,CHIP_H}}
};

View File

@ -885,7 +885,7 @@ const char *definesToChar(int defined) // converts the internally used #defined
const char *defNanoToChar[26] = {"D0", "D1", "D2", "D3", "D4", "D5", "D6", "D7", "D8", "D9", "D10", "D11", "D12", "D13", "RESET", "AREF", "A0", "A1", "A2", "A3", "A4", "A5", "A6", "A7"};
const char *defSpecialToChar[20] = {"GND", "NOT_DEFINED", "NOT_DEFINED", "3V3", "NOT_DEFINED", "5V", "DAC_0", "DAC_1", "I_POS", "I_NEG", "ADC_0" , "ADC_1" , "ADC_2" , "ADC_3", "GPIO_0", "NOT_DEFINED", "UART_Rx", "UART_Tx"};
const char *defSpecialToChar[20] = {"GND", "NOT_DEFINED", "NOT_DEFINED", "3V3", "NOT_DEFINED", "5V", "DAC_0", "DAC_1", "I_POS", "I_NEG", "ADC_0" , "ADC_1" , "ADC_2" , "ADC_3", "GPIO_0", "NOT_DEFINED", "UART_Tx", "UART_Rx"};
const char *emptyNet[] = {"EMPTY_NET", "?"};
@ -893,7 +893,7 @@ const char *definesToChar(int defined) // converts the internally used #defined
{
return defNanoToChar[defined - 70];
}
else if (defined >= 100 && defined <= RP_UART_TX)
else if (defined >= 100 && defined <= RP_UART_RX)
{
return defSpecialToChar[defined - 100];

View File

@ -739,16 +739,18 @@ void resolveAltPaths(void)
if (path[i].Lchip == true)
{
//Serial.print("Lchip");
if (ch[CHIP_L].yStatus[bb] == -1 || ch[CHIP_L].yStatus[bb] == path[i].net) /////////
{
int xMapL0c0 = xMapForChipLane0(path[i].chip[0], bb);
int xMapL1c0 = xMapForChipLane1(path[i].chip[0], bb);
int xMapL0c1 = xMapForChipLane0(bb, path[i].chip[0]);
int xMapL1c1 = xMapForChipLane1(bb, path[i].chip[0]);
int xMapL0c0 = xMapForChipLane0(path[i].chip[0], path[i].chip[bb]);
int xMapL1c0 = xMapForChipLane1(path[i].chip[0], path[i].chip[bb]);
int xMapL0c1 = xMapForChipLane0(path[i].chip[bb], path[i].chip[0]);
int xMapL1c1 = xMapForChipLane1(path[i].chip[bb], path[i].chip[0]);
int freeLane = -1;
@ -777,6 +779,7 @@ void resolveAltPaths(void)
if (freeLane == 0)
{
//Serial.print("Lchip!!!!!!!!!!!!");
ch[path[i].chip[0]].xStatus[xMapL0c0] = path[i].net;
ch[path[i].chip[1]].xStatus[xMapL0c1] = path[i].net;
@ -797,6 +800,7 @@ void resolveAltPaths(void)
}
else if (freeLane == 1)
{
//Serial.print("Lchip!!!!!!!!!!!22222!");
ch[path[i].chip[0]].xStatus[xMapL1c0] = path[i].net;
ch[path[i].chip[1]].xStatus[xMapL1c1] = path[i].net;
@ -2325,7 +2329,7 @@ void findStartAndEndChips(int node1, int node2, int pathIdx)
}
break;
}
case GND ... ADC3_8V:
case GND ... 126:
{
if (debugNTCC)
{
@ -2485,7 +2489,7 @@ void assignPathType(int pathIndex)
path[pathIndex].sameChip = false;
}
if ((path[pathIndex].node1 == 1 || path[pathIndex].node1 == 30 || path[pathIndex].node1 == 31 || path[pathIndex].node1 == 60) || path[pathIndex].chip[0] == CHIP_L)
if ((path[pathIndex].node1 == 1 || path[pathIndex].node1 == 30 || path[pathIndex].node1 == 31 || path[pathIndex].node1 == 60) || path[pathIndex].node1 == 114 || path[pathIndex].node1 == 116 || path[pathIndex].node1 == 117 || path[pathIndex].chip[0] == CHIP_L)
{
// Serial.print("\n\n\rthis should be a bb to sf connection\n\n\n\r ");
//path[pathIndex].altPathNeeded = true;
@ -2508,7 +2512,7 @@ void assignPathType(int pathIndex)
path[pathIndex].nodeType[0] = SF;
}
if ((path[pathIndex].node2 == 1 || path[pathIndex].node2 == 30 || path[pathIndex].node2 == 31 || path[pathIndex].node2 == 60) || path[pathIndex].chip[1] == CHIP_L)
if ((path[pathIndex].node2 == 1 || path[pathIndex].node2 == 30 || path[pathIndex].node2 == 31 || path[pathIndex].node2 == 60) || path[pathIndex].node2 == 114 || path[pathIndex].node2 == 116 || path[pathIndex].node2 == 117|| path[pathIndex].chip[1] == CHIP_L)
{
// Serial.print("\n\n\rthis should be a bb to sf connection 2\n\n\n\r ");
//path[pathIndex].altPathNeeded = true;

View File

@ -22,7 +22,7 @@
#include <SPI.h>
#define CSI Serial.write("\x1B\x5B");
//#define CSI Serial.write("\033");
// #define CSI Serial.write("\033");
#define DAC_RESOLUTION 9
@ -30,16 +30,14 @@ int revisionNumber = 0;
int showReadings = 0;
int showADCreadings[4] = {1,1,1,1};
int showINA0[3] = {1,1,1}; //0 = current, 1 = voltage, 2 = power
int showINA1[3] = {0, 0, 0}; //0 = current, 1 = voltage, 2 = power
int showADCreadings[4] = {1, 1, 1, 1};
int showINA0[3] = {1, 1, 1}; // 0 = current, 1 = voltage, 2 = power
int showINA1[3] = {0, 0, 0}; // 0 = current, 1 = voltage, 2 = power
int showDAC0 = 0;
int showDAC1 = 0;
float freq[3] = {1, 1, 0};
uint32_t period[3] = {0, 0, 0};
uint32_t halvePeriod[3] = {0, 0, 0};
@ -93,8 +91,8 @@ void initADC(void)
void initDAC(void)
{
Wire.begin();
delay(5);
Wire.begin();
delay(5);
if (dac1_8V.begin(MCP4725A1_Addr_A01, i2c0, 400, 4, 5) == true)
{
revisionNumber = 2;
@ -129,17 +127,17 @@ void initDAC(void)
SPI.setCS(1);
SPI.setSCK(2);
SPI.setTX(3);
SPI.begin();
//dac_rev3.maxValue = 4095;
delay(5);
// dac_rev3.maxValue = 4095;
delay(5);
dac_rev3.setGain(2);
delay(5);
delay(5);
dac_rev3.begin(1);
delay(5);
setDac0_5Vvoltage(0.00);
// setDac0_5VinputCode(4095);
// setDac0_5VinputCode(4095);
setDac1_8VinputCode(4095);
}
@ -222,11 +220,10 @@ void setDac0_5Vvoltage(float voltage)
{
int voltageCode = voltage * 4095 / 5;
// dac_rev3.analogWrite((uint16_t)voltageCode, 0);
dac_rev3.fastWriteA((uint16_t)voltageCode);
lastInputCode0 = voltageCode;
//dac_rev3.fastWriteB(lastInputCode1);
// dac_rev3.fastWriteB(lastInputCode1);
}
}
@ -241,7 +238,7 @@ void setDac0_5VinputCode(uint16_t inputCode)
dac_rev3.analogWrite(inputCode, 0);
dac_rev3.fastWriteA(inputCode);
lastInputCode0 = inputCode;
//dac_rev3.fastWriteB(lastInputCode1);
// dac_rev3.fastWriteB(lastInputCode1);
}
}
@ -259,8 +256,8 @@ void setDac1_8Vvoltage(float voltage)
// dac_rev3.analogWrite((uint16_t)voltageCode, 1);
dac_rev3.fastWriteB((uint16_t)voltageCode);
///lastInputCode1 = voltageCode;
// dac_rev3.fastWriteA(lastInputCode0);
/// lastInputCode1 = voltageCode;
// dac_rev3.fastWriteA(lastInputCode0);
}
}
@ -276,8 +273,8 @@ void setDac1_8VinputCode(uint16_t inputCode)
// Serial.println(inputCode);
// dac_rev3.analogWrite(inputCode, 1);
dac_rev3.fastWriteB(inputCode);
//lastInputCode1 = inputCode;
// dac_rev3.fastWriteA(lastInputCode0);
// lastInputCode1 = inputCode;
// dac_rev3.fastWriteA(lastInputCode0);
}
}
@ -288,9 +285,6 @@ void chooseShownReadings(void)
showADCreadings[2] = 0;
showADCreadings[3] = 0;
for (int i = 0; i <= newBridgeIndex; i++)
{
@ -299,7 +293,7 @@ void chooseShownReadings(void)
showADCreadings[0] = 1;
}
if (path[i].node1 == ADC1_5V || path[i].node2 == ADC1_5V)
if (path[i].node1 == ADC1_5V || path[i].node2 == ADC1_5V)
{
showADCreadings[1] = 1;
}
@ -339,141 +333,126 @@ void chooseShownReadings(void)
break;
}
}
}
}
void showMeasurements(int samples)
{
while (Serial.available() == 0)
{
//CSI
//Serial.write("\x1B\x5B 2K");
//Serial.write("2K");
Serial.print("\r \r");
int adc0ReadingUnscaled;
float adc0Reading;
int adc1ReadingUnscaled;
float adc1Reading;
int adc2ReadingUnscaled;
float adc2Reading;
int adc3ReadingUnscaled;
float adc3Reading;
int bs = 0;
if (showADCreadings[0] == 1)
while (Serial.available() == 0)
{
// CSI
// Serial.write("\x1B\x5B 2K");
// Serial.write("2K");
adc0ReadingUnscaled = readAdc(0, samples);
adc0Reading = (adc0ReadingUnscaled) * (5.0 / 4095);
//adc0Reading -= 0.1; // offset
bs+= Serial.print("D0: ");
bs+=Serial.print(adc0Reading);
bs+=Serial.print("V\t");
Serial.print("\r \r");
int adc0ReadingUnscaled;
float adc0Reading;
int adc1ReadingUnscaled;
float adc1Reading;
int adc2ReadingUnscaled;
float adc2Reading;
int adc3ReadingUnscaled;
float adc3Reading;
int bs = 0;
if (showADCreadings[0] == 1)
{
adc0ReadingUnscaled = readAdc(0, samples);
adc0Reading = (adc0ReadingUnscaled) * (5.0 / 4095);
// adc0Reading -= 0.1; // offset
bs += Serial.print("D0: ");
bs += Serial.print(adc0Reading);
bs += Serial.print("V\t");
}
if (showADCreadings[1] == 1)
{
adc1ReadingUnscaled = readAdc(1, samples);
adc1Reading = (adc1ReadingUnscaled) * (5.0 / 4095);
// adc1Reading -= 0.1; // offset
bs += Serial.print("D1: ");
bs += Serial.print(adc1Reading);
bs += Serial.print("V\t");
}
if (showADCreadings[2] == 1)
{
adc2ReadingUnscaled = readAdc(2, samples);
adc2Reading = (adc2ReadingUnscaled) * (5.0 / 4095);
// adc2Reading -= 0.1; // offset
bs += Serial.print("D2: ");
bs += Serial.print(adc2Reading);
bs += Serial.print("V\t");
}
if (showADCreadings[3] == 1)
{
adc3ReadingUnscaled = readAdc(3, samples);
adc3Reading = (adc3ReadingUnscaled) * (16.0 / 4010);
adc3Reading -= 8.7; // offset
bs += Serial.print("D3: ");
bs += Serial.print(adc3Reading);
bs += Serial.print("V\t");
}
if (showINA0[0] == 1 || showINA0[1] == 1 || showINA0[2] == 1)
{
bs += Serial.print(" INA219: ");
}
if (showINA0[0] == 1)
{
bs += Serial.print("I: ");
bs += Serial.print(INA0.getCurrent_mA());
bs += Serial.print("mA\t");
}
if (showINA0[1] == 1)
{
bs += Serial.print(" V: ");
bs += Serial.print(INA0.getBusVoltage());
bs += Serial.print("V\t");
}
if (showINA0[2] == 1)
{
bs += Serial.print("P: ");
bs += Serial.print(INA0.getPower_mW());
bs += Serial.print("mW\t");
}
bs += Serial.print(" \r");
// for (int i = 0; i < bs; i++)
// {
// Serial.print("\b");
// }
// Serial.print("ADC1: ");
// Serial.print(adc1ReadingUnscaled);
// Serial.print("V\n\r");
// Serial.print("ADC2: ");
// Serial.print(adc2ReadingUnscaled);
// Serial.print("V\n\r");
// Serial.print("ADC3: ");
// Serial.print(adc3ReadingUnscaled);
// Serial.print("V\n\n\r");
delay(350);
}
if (showADCreadings[1] == 1)
{
adc1ReadingUnscaled = readAdc(1, samples);
adc1Reading = (adc1ReadingUnscaled) * (5.0 / 4095);
//adc1Reading -= 0.1; // offset
bs+=Serial.print("D1: ");
bs+=Serial.print(adc1Reading);
bs+=Serial.print("V\t");
}
if (showADCreadings[2] == 1)
{
adc2ReadingUnscaled = readAdc(2, samples);
adc2Reading = (adc2ReadingUnscaled) * (5.0 / 4095);
//adc2Reading -= 0.1; // offset
bs+=Serial.print("D2: ");
bs+=Serial.print(adc2Reading);
bs+=Serial.print("V\t");
}
if (showADCreadings[3] == 1)
{
adc3ReadingUnscaled = readAdc(3, samples);
adc3Reading = (adc3ReadingUnscaled) * (16.0 / 4010);
adc3Reading -= 8.7; // offset
bs+=Serial.print("D3: ");
bs+=Serial.print(adc3Reading);
bs+=Serial.print("V\t");
}
if (showINA0[0] == 1 || showINA0[1] == 1 || showINA0[2] == 1)
{
bs+=Serial.print(" INA219: ");
}
if (showINA0[0] == 1)
{
bs+=Serial.print("I: ");
bs+=Serial.print(INA0.getCurrent_mA());
bs+=Serial.print("mA\t");
}
if (showINA0[1] == 1)
{
bs+=Serial.print(" V: ");
bs+=Serial.print(INA0.getBusVoltage());
bs+=Serial.print("V\t");
}
if (showINA0[2] == 1)
{
bs+=Serial.print("P: ");
bs+=Serial.print(INA0.getPower_mW());
bs+=Serial.print("mW\t");
}
bs+=Serial.print(" \r");
// for (int i = 0; i < bs; i++)
// {
// Serial.print("\b");
// }
// Serial.print("ADC1: ");
// Serial.print(adc1ReadingUnscaled);
// Serial.print("V\n\r");
// Serial.print("ADC2: ");
// Serial.print(adc2ReadingUnscaled);
// Serial.print("V\n\r");
// Serial.print("ADC3: ");
// Serial.print(adc3ReadingUnscaled);
// Serial.print("V\n\n\r");
delay(350);
}
}
int readAdc(int channel, int samples)
{
int adcReadingAverage = 0;
uint8_t adcChannel = channel+ ADC0_PIN;
uint8_t adcChannel = channel + ADC0_PIN;
for (int i = 0; i < samples; i++)
{
@ -543,38 +522,37 @@ int waveGen(void)
int adc0Reading = 0;
int brightness0 = 0;
int hueShift0 = 0;
//firstCrossFreq0 = 1;
// firstCrossFreq0 = 1;
if (dacOn[0] == 1&& freq[0] < 33)
if (dacOn[0] == 1 && freq[0] < 33)
{
//adc0Reading = INA1.getBusVoltage_mV();
// adc0Reading = dac0_5V.getInputCode();
// adc0Reading = INA1.getBusVoltage_mV();
// adc0Reading = dac0_5V.getInputCode();
if (c == 'q')
{
} else {
}
else
{
adc0Reading = readAdc(26, 1);
adc0Reading = abs(adc0Reading);
hueShift0 = map(adc0Reading, 0, 5000, -90, 0);
brightness0 = map(adc0Reading, 0, 5000, 4, 100);
lightUpNet(4, -1, 1, brightness0, hueShift0);
showLEDsCore2 = 1;
firstCrossFreq0 = 1;
adc0Reading = readAdc(26, 1);
adc0Reading = abs(adc0Reading);
hueShift0 = map(adc0Reading, 0, 5000, -90, 0);
brightness0 = map(adc0Reading, 0, 5000, 4, 100);
lightUpNet(4, -1, 1, brightness0, hueShift0);
showLEDsCore2 = 1;
firstCrossFreq0 = 1;
}
}
else
{
if (firstCrossFreq0 == 1)
{
lightUpNet(4);
showLEDsCore2 = 1;
firstCrossFreq0 = 0;
lightUpNet(4);
showLEDsCore2 = 1;
firstCrossFreq0 = 0;
}
}
int adc1Reading = 0;
@ -584,14 +562,12 @@ int waveGen(void)
if (dacOn[1] == 1 && freq[1] < 17)
{
adc1Reading = readAdc(29, 1);
hueShift1 = map(adc1Reading, -2048, 2048, -50, 45);
adc1Reading = adc1Reading - 2048;
adc1Reading = abs(adc1Reading);
brightness1 = map(adc1Reading, 0, 2050, 4, 100);
hueShift1 = map(adc1Reading, -2048, 2048, -50, 45);
adc1Reading = adc1Reading - 2048;
adc1Reading = abs(adc1Reading);
brightness1 = map(adc1Reading, 0, 2050, 4, 100);
lightUpNet(5, -1, 1, brightness1, hueShift1);
showLEDsCore2 = 1;
@ -601,9 +577,9 @@ int waveGen(void)
{
if (firstCrossFreq1 == 1)
{
lightUpNet(5);
showLEDsCore2 = 1;
firstCrossFreq1 = 0;
lightUpNet(5);
showLEDsCore2 = 1;
firstCrossFreq1 = 0;
}
}
@ -841,22 +817,21 @@ int waveGen(void)
setDac0_5VinputCode(amplitude[activeDac]);
lightUpNet(4, -1, 1, DEFAULTSPECIALNETBRIGHTNESS, 12);
showLEDsCore2 = 1;
}
}
else if (activeDac == 1 && dacOn[activeDac] == 1)
{
setDac1_8VinputCode(amplitude[activeDac]);
showLEDsCore2 = 1;
}
}
else
{
if (activeDac == 0 && dacOn[activeDac] == 1)
{
setDac0_5VinputCode(0);
lightUpNet(4, -1, 1, 2, 12);
}
lightUpNet(4, -1, 1, 2, 12);
}
else if (activeDac == 1 && dacOn[activeDac] == 1)
{

View File

@ -1,6 +1,22 @@
#include <Arduino.h>
#define USE_TINYUSB 1
#define LED LED_BUILTIN
#ifdef USE_TINYUSB
#include <Adafruit_TinyUSB.h>
#endif
#ifdef CFG_TUSB_CONFIG_FILE
#include CFG_TUSB_CONFIG_FILE
#else
#include "tusb_config.h"
#endif
#include "ArduinoStuff.h"
#include "JumperlessDefinesRP2040.h"
#include "NetManager.h"
#include "MatrixStateRP2040.h"
@ -12,7 +28,6 @@
#include <Wire.h>
#include <Adafruit_NeoPixel.h>
// #include <EEPROM.h>
#include "ArduinoStuff.h"
#ifdef EEPROMSTUFF
#include <EEPROM.h>
@ -29,17 +44,26 @@
#endif
Adafruit_USBD_CDC USBSer1;
volatile int sendAllPathsCore2 = 0; // this signals the core 2 to send all the paths to the CH446Q
// https://wokwi.com/projects/367384677537829889
void setup()
{
pinMode(0, OUTPUT);
pinMode(2, INPUT);
pinMode(3, INPUT);
// initArduino();
// debugFlagInit();
USBDevice.setProductDescriptor("Jumperless");
USBDevice.setManufacturerDescriptor("Architeuthis Flux");
USBDevice.setSerialDescriptor("0");
USBDevice.setID(0xACAB, 0x1312);
USBSer1.setStringDescriptor("Jumperless USB Serial");
USBSer1.begin(115200);
#ifdef EEPROMSTUFF
EEPROM.begin(256);
@ -54,6 +78,8 @@ void setup()
initINA219();
delay(1);
Serial.begin(115200);
initArduino();
delay(4);
#ifdef FSSTUFF
LittleFS.begin();
@ -74,10 +100,12 @@ void setup1()
// delay (4);
initLEDs();
delay(4);
startupColors();
delay(4);
lightUpRail();
delay(4);
showLEDsCore2 = 1;
}
@ -128,23 +156,23 @@ dontshowmenu:
}
else
{
showReadings++;
showReadings++;
chooseShownReadings();
//Serial.write("\033");
//Serial.write("\x1B\x5B");
//Serial.write("1F");//scroll up one line
//Serial.write("\x1B\x5B");
//Serial.write("\033");
//Serial.write("2K");//clear line
//Serial.write("\033");
//Serial.write("\x1B\x5B");
// Serial.write("1F");//scroll up one line
//Serial.write("\x1B\x5B");
//Serial.write("\033");
//Serial.write("2K");//clear line
// Serial.write("\033");
// Serial.write("\x1B\x5B");
// Serial.write("1F");//scroll up one line
// Serial.write("\x1B\x5B");
// Serial.write("\033");
// Serial.write("2K");//clear line
// Serial.write("\033");
// Serial.write("\x1B\x5B");
// Serial.write("1F");//scroll up one line
// Serial.write("\x1B\x5B");
// Serial.write("\033");
// Serial.write("2K");//clear line
goto dontshowmenu;
//break;
// break;
}
case 'n':
@ -184,17 +212,12 @@ dontshowmenu:
// }
case 'f':
digitalWrite(RESETPIN, HIGH);
clearAllNTCC();
// delay(1);
// showLEDsCore2 = 1;
// delay(5);
// resetArduino();
sendAllPathsCore2 = 1;
//sendAllPathsCore2 = 1;
timer = millis();
#ifdef FSSTUFF
clearNodeFile();
@ -203,10 +226,13 @@ dontshowmenu:
openNodeFile();
getNodesToConnect();
#endif
digitalWrite(RESETPIN, LOW);
digitalWrite(RESETPIN, HIGH);
bridgesToPaths();
clearLEDs();
assignNetColors();
digitalWrite(RESETPIN, LOW);
// showNets();
#ifdef PIOSTUFF
@ -314,7 +340,9 @@ dontshowmenu:
break;
case 'r':
resetArduino();
break;
case 'd':
@ -384,6 +412,9 @@ dontshowmenu:
}
unsigned long logoFlashTimer = 0;
int arduinoReset = 0;
unsigned long lastTimeReset = 0;
void loop1() // core 2 handles the LEDs and the CH446Q8
{
@ -433,4 +464,31 @@ void loop1() // core 2 handles the LEDs and the CH446Q8
leds.setPixelColor(110, 0x550008);
leds.show();
}
if (arduinoReset == 0 && USBSer1.peek() == 0x30) // 0x30 is the first thing AVRDUDE sends
{
resetArduino();
arduinoReset = 1;
lastTimeReset = millis();
}
if (USBSer1.available())
{
char ch = USBSer1.read();
Serial1.write(ch);
}
if (Serial1.available())
{
char ch = Serial1.read();
USBSer1.write(ch);
}
if (millis() - lastTimeReset > 1000) //if the arduino hasn't been reset in a second, reset the flag
{
arduinoReset = 0;
}
}