mirror of
https://github.com/Architeuthis-Flux/Jumperless.git
synced 2024-11-27 17:00:55 +01:00
now you can load wokwi diagram files
This commit is contained in:
parent
5795ceb838
commit
c9e82ff577
10
JumperlessNano/.vscode/extensions 2.json
vendored
Normal file
10
JumperlessNano/.vscode/extensions 2.json
vendored
Normal file
@ -0,0 +1,10 @@
|
|||||||
|
{
|
||||||
|
// See http://go.microsoft.com/fwlink/?LinkId=827846
|
||||||
|
// for the documentation about the extensions.json format
|
||||||
|
"recommendations": [
|
||||||
|
"platformio.platformio-ide"
|
||||||
|
],
|
||||||
|
"unwantedRecommendations": [
|
||||||
|
"ms-vscode.cpptools-extension-pack"
|
||||||
|
]
|
||||||
|
}
|
@ -2,11 +2,13 @@ bridges
|
|||||||
{
|
{
|
||||||
10-33,
|
10-33,
|
||||||
23-57,
|
23-57,
|
||||||
}
|
|
||||||
|
|
||||||
special functions //these are connected first so DNIs will be applied to all the nets
|
|
||||||
{
|
|
||||||
20-SUPPLY_3V3,
|
20-SUPPLY_3V3,
|
||||||
58-GND,
|
58-GND,
|
||||||
|
57-DAC0_5V,
|
||||||
|
47-I_P,
|
||||||
|
45-I_N,
|
||||||
|
DAC1_8V-36,
|
||||||
|
ADC3_8V-2,
|
||||||
|
ADC0_5V-DAC0_5V,
|
||||||
}
|
}
|
||||||
|
|
0
JumperlessNano/data/wokwi.txt
Normal file
0
JumperlessNano/data/wokwi.txt
Normal file
56
JumperlessNano/diagram.json
Normal file
56
JumperlessNano/diagram.json
Normal file
@ -0,0 +1,56 @@
|
|||||||
|
{
|
||||||
|
"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": -675.6,
|
||||||
|
"left": -82.6,
|
||||||
|
"attrs": { "color": "red" }
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"type": "wokwi-resistor",
|
||||||
|
"id": "r1",
|
||||||
|
"top": -600.85,
|
||||||
|
"left": -57.6,
|
||||||
|
"attrs": { "value": "1000" }
|
||||||
|
},
|
||||||
|
{ "type": "wokwi-gnd", "id": "gnd1", "top": -1036.8, "left": -77.4, "attrs": {} },
|
||||||
|
{ "type": "wokwi-vcc", "id": "vcc1", "top": -901.13, "left": 98.33, "attrs": {} }
|
||||||
|
],
|
||||||
|
"connections": [
|
||||||
|
[ "bb1:15b.j", "nano:12", "gold", [ "v0" ] ],
|
||||||
|
[ "bb1:19b.j", "nano:9", "green", [ "h93.92", "v-248.6" ] ],
|
||||||
|
[ "nano:A2", "bb1:tn.8", "orange", [ "v0" ] ],
|
||||||
|
[ "r1:2", "bb1:13t.a", "green", [ "v0" ] ],
|
||||||
|
[ "bb1:17t.d", "nano:A5", "purple", [ "v0" ] ],
|
||||||
|
[ "r1:1", "bb1:7t.c", "green", [ "v0" ] ],
|
||||||
|
[ "bb1:9b.g", "bb1:9b.i", "green", [ "v0" ] ],
|
||||||
|
[ "bb1:20t.c", "bb1:23t.c", "green", [ "v0" ] ],
|
||||||
|
[ "bb1:5b.j", "bb1:11b.j", "green", [ "v0" ] ],
|
||||||
|
[ "bb1:13b.i", "bb1:14t.d", "limegreen", [ "v0" ] ],
|
||||||
|
[ "bb1:bn.10", "gnd1:GND", "black", [ "v0" ] ],
|
||||||
|
[ "vcc1:VCC", "bb1:tp.19", "red", [ "v191.81", "h-4.49" ] ],
|
||||||
|
[ "bb1:22t.c", "bb1:tn.18", "green", [ "v0" ] ],
|
||||||
|
[ "bb1:tn.1", "bb1:bn.1", "green", [ "h-35.16", "v174" ] ],
|
||||||
|
[ "bb1:tp.1", "bb1:bp.2", "green", [ "h-74.06", "v174" ] ],
|
||||||
|
[ "nano:3", "nano:1", "green", [ "v0" ] ],
|
||||||
|
[ "nano:GND.1", "bb1:tn.17", "black", [ "v0" ] ],
|
||||||
|
[ "nano:AREF", "bb1:tp.6", "green", [ "v0" ] ],
|
||||||
|
[ "bb1:1b.j", "bb1:3b.h", "green", [ "v0" ] ],
|
||||||
|
[ "nano:5V", "bb1:tp.16", "red", [ "v0" ] ],
|
||||||
|
[ "nano:3.3V", "bb1:tn.7", "green", [ "v0" ] ],
|
||||||
|
[ "nano:VIN", "bb1:tn.19", "red", [ "v0" ] ],
|
||||||
|
[ "led1:A", "bb1:7t.b", "", [ "$bb" ] ],
|
||||||
|
[ "led1:C", "bb1:6t.b", "", [ "$bb" ] ],
|
||||||
|
[ "bb1:bn.15", "bb1:18b.j", "green", [ "v0" ] ],
|
||||||
|
[ "nano:GND.1", "bb1:bn.16", "black", [ "v0" ] ],
|
||||||
|
[ "gnd1:GND", "bb1:tn.3", "black", [ "v0" ] ],
|
||||||
|
[ "bb1:6t.c", "bb1:tp.2", "green", [ "v0" ] ]
|
||||||
|
],
|
||||||
|
"dependencies": {}
|
||||||
|
}
|
@ -13,9 +13,18 @@ platform = https://github.com/maxgerhardt/platform-raspberrypi.git
|
|||||||
framework = arduino
|
framework = arduino
|
||||||
board_build.core = earlephilhower
|
board_build.core = earlephilhower
|
||||||
board_build.filesystem_size = 0.5m
|
board_build.filesystem_size = 0.5m
|
||||||
|
upload_port = /dev/cu.usbmodem1301
|
||||||
|
monitor_port = /dev/cu.usbmodem1301
|
||||||
|
extra_scripts = post:scripts/extra_script.py
|
||||||
|
|
||||||
[env:pico]
|
[env:pico]
|
||||||
board = pico
|
board = pico
|
||||||
lib_deps =
|
lib_deps =
|
||||||
powerbroker2/SafeString@^4.1.27
|
powerbroker2/SafeString@^4.1.27
|
||||||
adafruit/Adafruit NeoPixel@^1.11.0
|
adafruit/Adafruit NeoPixel@^1.11.0
|
||||||
|
adafruit/Adafruit MCP4725@^2.0.0
|
||||||
|
adafruit/Adafruit INA219@^1.2.1
|
||||||
|
robtillaart/MCP4725@^0.3.5
|
||||||
|
robtillaart/INA219@^0.1.3
|
||||||
|
bblanchon/ArduinoJson@^6.21.2
|
||||||
|
arduino-libraries/Arduino_JSON@^0.2.0
|
||||||
|
24
JumperlessNano/scripts/extra_script.py
Normal file
24
JumperlessNano/scripts/extra_script.py
Normal file
@ -0,0 +1,24 @@
|
|||||||
|
Import("env")
|
||||||
|
|
||||||
|
def after_upload(source, target, env):
|
||||||
|
port = env.GetProjectOption("monitor_port")
|
||||||
|
print("waiting for " + port + " ...")
|
||||||
|
import serial
|
||||||
|
while True:
|
||||||
|
try:
|
||||||
|
s = serial.Serial(port)
|
||||||
|
break
|
||||||
|
except:
|
||||||
|
pass
|
||||||
|
|
||||||
|
env.AddPostAction("upload", after_upload)
|
||||||
|
|
||||||
|
|
||||||
|
# Custom HEX from ELF
|
||||||
|
env.AddPostAction(
|
||||||
|
"$BUILD_DIR/${PROGNAME}.elf",
|
||||||
|
env.VerboseAction(" ".join([
|
||||||
|
"$OBJCOPY", "-O", "ihex", "-R", ".eeprom",
|
||||||
|
'"$BUILD_DIR/${PROGNAME}.elf"', '"$BUILD_DIR/${PROGNAME}.hex"'
|
||||||
|
]), "Building $BUILD_DIR/${PROGNAME}.hex")
|
||||||
|
)
|
@ -5,15 +5,15 @@
|
|||||||
#include "LEDs.h"
|
#include "LEDs.h"
|
||||||
#include "Peripherals.h"
|
#include "Peripherals.h"
|
||||||
#include "JumperlessDefinesRP2040.h"
|
#include "JumperlessDefinesRP2040.h"
|
||||||
// #include <SPI.h>
|
|
||||||
// #include "pico/stdlib.h"
|
|
||||||
#include "hardware/pio.h"
|
#include "hardware/pio.h"
|
||||||
|
|
||||||
// #include "hardware/clocks.h"
|
|
||||||
// #include "ch446.pio.h"
|
|
||||||
#include "spi.pio.h"
|
#include "spi.pio.h"
|
||||||
#include "pio_spi.h"
|
#include "pio_spi.h"
|
||||||
// #include "ch446_spi.pio.h"
|
|
||||||
|
#define MYNAMEISERIC 0 //on the board I sent to eric, the data and clock lines are bodged to GPIO 18 and 19. To allow for using hardware SPI
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
int chipToPinArray[12] = {CS_A, CS_B, CS_C, CS_D, CS_E, CS_F, CS_G, CS_H, CS_I, CS_J, CS_K, CS_L};
|
int chipToPinArray[12] = {CS_A, CS_B, CS_C, CS_D, CS_E, CS_F, CS_G, CS_H, CS_I, CS_J, CS_K, CS_L};
|
||||||
PIO pio = pio0;
|
PIO pio = pio0;
|
||||||
@ -119,8 +119,18 @@ void isrFromPio(void)
|
|||||||
void initCH446Q(void)
|
void initCH446Q(void)
|
||||||
{
|
{
|
||||||
|
|
||||||
uint dat = 19;
|
uint dat = 14;
|
||||||
uint clk = 18;
|
uint clk = 15;
|
||||||
|
|
||||||
|
|
||||||
|
if (MYNAMEISERIC)
|
||||||
|
{
|
||||||
|
dat = 18;
|
||||||
|
clk = 19;
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
uint cs = 7;
|
uint cs = 7;
|
||||||
|
|
||||||
irq_add_shared_handler(PIO0_IRQ_0, isrFromPio, PICO_SHARED_IRQ_HANDLER_DEFAULT_ORDER_PRIORITY);
|
irq_add_shared_handler(PIO0_IRQ_0, isrFromPio, PICO_SHARED_IRQ_HANDLER_DEFAULT_ORDER_PRIORITY);
|
||||||
@ -175,16 +185,20 @@ void sendAllPaths(void) // should we sort them by chip? for now, no
|
|||||||
|
|
||||||
for (int i = 0; i < numberOfPaths; i++)
|
for (int i = 0; i < numberOfPaths; i++)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
|
||||||
sendPath(i, 1);
|
sendPath(i, 1);
|
||||||
|
|
||||||
delay(1200);
|
|
||||||
|
|
||||||
|
//delay(120);
|
||||||
}
|
}
|
||||||
for (int i = numberOfPaths; i >= 0; i--)
|
/*for (int i = numberOfPaths; i >= 0; i--)
|
||||||
{
|
{
|
||||||
sendPath(i, 0);
|
sendPath(i, 0);
|
||||||
|
|
||||||
delay(800);
|
delay(800);
|
||||||
}
|
}*/
|
||||||
}
|
}
|
||||||
|
|
||||||
void sendPath(int i, int setOrClear)
|
void sendPath(int i, int setOrClear)
|
||||||
@ -211,8 +225,8 @@ void sendPath(int i, int setOrClear)
|
|||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
||||||
lightUpNet(path[i].net, path[i].node1, setOrClear);
|
lightUpNet(path[i].net, path[i].node1, setOrClear,255);
|
||||||
lightUpNet(path[i].net, path[i].node2, setOrClear);
|
lightUpNet(path[i].net, path[i].node2, setOrClear,255);
|
||||||
|
|
||||||
chYdata = path[i].y[chip];
|
chYdata = path[i].y[chip];
|
||||||
chXdata = path[i].x[chip];
|
chXdata = path[i].x[chip];
|
||||||
|
@ -3,37 +3,389 @@
|
|||||||
#include "LittleFS.h"
|
#include "LittleFS.h"
|
||||||
#include "MatrixStateRP2040.h"
|
#include "MatrixStateRP2040.h"
|
||||||
#include "SafeString.h"
|
#include "SafeString.h"
|
||||||
|
#include "ArduinoJson.h"
|
||||||
#include "NetManager.h"
|
#include "NetManager.h"
|
||||||
|
#include "JumperlessDefinesRP2040.h"
|
||||||
|
#include "LEDs.h"
|
||||||
|
|
||||||
|
|
||||||
static bool debugFP;
|
static bool debugFP;
|
||||||
static bool debugFPtime;
|
static bool debugFPtime;
|
||||||
|
|
||||||
createSafeString(nodeFileString, 1200);
|
createSafeString(nodeFileString, 1200);
|
||||||
createSafeString(bridgeString, 800);
|
|
||||||
createSafeString(specialFunctionsString, 400);
|
createSafeString(nodeString, 1200);
|
||||||
|
createSafeString(specialFunctionsString, 800);
|
||||||
|
|
||||||
|
char inputBuffer[5000] = {0};
|
||||||
|
|
||||||
|
ArduinoJson::StaticJsonDocument<5000> wokwiJson;
|
||||||
|
|
||||||
|
String connectionsW[MAX_BRIDGES][5];
|
||||||
|
|
||||||
File nodeFile;
|
File nodeFile;
|
||||||
|
File wokwiFile;
|
||||||
|
|
||||||
unsigned long timeToFP = 0;
|
unsigned long timeToFP = 0;
|
||||||
|
|
||||||
|
int numConnsJson = 0;
|
||||||
|
|
||||||
|
void parseWokwiFileToNodeFile(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
delay(3000);
|
||||||
|
LittleFS.begin();
|
||||||
|
timeToFP = millis();
|
||||||
|
if (DEBUG_FILEPARSING == 1)
|
||||||
|
debugFP = true; // yeah we're using runtime debug flags so it can be toggled from commands
|
||||||
|
else
|
||||||
|
debugFP = false;
|
||||||
|
if (TIME_FILEPARSING == 1)
|
||||||
|
debugFPtime = true;
|
||||||
|
else
|
||||||
|
debugFPtime = false;
|
||||||
|
|
||||||
|
wokwiFile = LittleFS.open("wokwi.txt", "w+");
|
||||||
|
if (!wokwiFile)
|
||||||
|
{
|
||||||
|
if (debugFP)
|
||||||
|
Serial.println("Failed to open wokwi.txt");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
if (debugFP)
|
||||||
|
Serial.println("\n\ropened wokwi.txt\n\n\n\r");
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial.println("paste Wokwi diagram.json here");
|
||||||
|
while (Serial.available() == 0)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
int numCharsRead = 0;
|
||||||
|
|
||||||
|
while (Serial.available() > 0)
|
||||||
|
{
|
||||||
|
char c = Serial.read();
|
||||||
|
inputBuffer[numCharsRead] = c;
|
||||||
|
|
||||||
|
numCharsRead++;
|
||||||
|
delay(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
createSafeStringFromCharArray(wokwiFileString, inputBuffer);
|
||||||
|
delay(10);
|
||||||
|
wokwiFile.write(inputBuffer, numCharsRead);
|
||||||
|
|
||||||
|
delay(10);
|
||||||
|
|
||||||
|
wokwiFile.seek(0);
|
||||||
|
|
||||||
|
|
||||||
|
Serial.println("\n\n\rwokwiFile\n\n\r");
|
||||||
|
|
||||||
|
/* for (int i = 0; i < numCharsRead; i++)
|
||||||
|
{
|
||||||
|
Serial.print((char)wokwiFile.read());
|
||||||
|
}*/
|
||||||
|
|
||||||
|
Serial.print(wokwiFileString);
|
||||||
|
|
||||||
|
Serial.println("\n\n\rnumCharsRead\n\n\r");
|
||||||
|
|
||||||
|
Serial.print(numCharsRead);
|
||||||
|
|
||||||
|
wokwiFile.close();
|
||||||
|
|
||||||
|
deserializeJson(wokwiJson, inputBuffer);
|
||||||
|
|
||||||
|
Serial.println("\n\n\rwokwiJson\n\n\r");
|
||||||
|
|
||||||
|
//serializeJsonPretty(wokwiJson, Serial);
|
||||||
|
Serial.println("\n\n\rconnectionsW\n\n\r");
|
||||||
|
|
||||||
|
numConnsJson = wokwiJson["connections"].size();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
copyArray(wokwiJson["connections"], connectionsW);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//deserializeJson(connectionsW, Serial);
|
||||||
|
Serial.println(wokwiJson["connections"].size());
|
||||||
|
|
||||||
|
|
||||||
|
for (int i = 0; i < MAX_BRIDGES; i++)
|
||||||
|
{
|
||||||
|
//Serial.println(wokwiJson["connections"].size());
|
||||||
|
if (connectionsW[i][0] == "")
|
||||||
|
{
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
Serial.print(connectionsW[i][0]);
|
||||||
|
Serial.print(", \t ");
|
||||||
|
|
||||||
|
Serial.print(connectionsW[i][1]);
|
||||||
|
Serial.print(", \t ");
|
||||||
|
|
||||||
|
Serial.print(connectionsW[i][2]);
|
||||||
|
Serial.print(", \t ");
|
||||||
|
|
||||||
|
Serial.print(connectionsW[i][3]);
|
||||||
|
Serial.print(", \t ");
|
||||||
|
|
||||||
|
Serial.print(connectionsW[i][4]);
|
||||||
|
Serial.print(", \t ");
|
||||||
|
|
||||||
|
Serial.println();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial.println("\n\n\rRedefining\n\n\r");
|
||||||
|
|
||||||
|
|
||||||
|
changeWokwiDefinesToJumperless();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
writeToNodeFile();
|
||||||
|
//while(1);
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void changeWokwiDefinesToJumperless(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
String connString1 = " ";
|
||||||
|
String connString2 = " ";
|
||||||
|
String connStringColor = " ";
|
||||||
|
String bb = "bb1:";
|
||||||
|
|
||||||
|
|
||||||
|
int nodeNumber;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
for (int i = 0; i < numConnsJson; i++)
|
||||||
|
{
|
||||||
|
Serial.println(' ');
|
||||||
|
|
||||||
|
for (int j = 0; j < 2; j++)
|
||||||
|
{
|
||||||
|
nodeNumber = -1;
|
||||||
|
connString1 = connectionsW[i][j];
|
||||||
|
Serial.print(connString1);
|
||||||
|
Serial.print(" \t\t ");
|
||||||
|
|
||||||
|
if (connString1.startsWith("bb1:") || connString1.startsWith("bb2:"))
|
||||||
|
{
|
||||||
|
//Serial.print("bb1 or bb2 ");
|
||||||
|
|
||||||
|
int periodIndex = connString1.indexOf(".");
|
||||||
|
connString1 = connString1.substring(4,periodIndex);
|
||||||
|
|
||||||
|
if (connString1.endsWith("b"))
|
||||||
|
{
|
||||||
|
nodeNumber = 30;
|
||||||
|
//Serial.println("bottom");
|
||||||
|
connString1.substring(0,connString1.length()-1);
|
||||||
|
nodeNumber += connString1.toInt();
|
||||||
|
}
|
||||||
|
else if (connString1.endsWith("t"))
|
||||||
|
{
|
||||||
|
nodeNumber = 0;
|
||||||
|
//Serial.println("top");
|
||||||
|
connString1.substring(0,connString1.length()-1);
|
||||||
|
nodeNumber += connString1.toInt();
|
||||||
|
} else if (connString1.endsWith("n"))
|
||||||
|
{
|
||||||
|
nodeNumber = GND;
|
||||||
|
} else if (connString1.endsWith("p"))
|
||||||
|
{
|
||||||
|
nodeNumber = SUPPLY_5V;
|
||||||
|
}
|
||||||
|
|
||||||
|
} else if (connString1.startsWith("nano:"))
|
||||||
|
{
|
||||||
|
//Serial.print("nano\t");
|
||||||
|
int periodIndex = connString1.indexOf(".");
|
||||||
|
connString1 = connString1.substring(5,periodIndex);
|
||||||
|
|
||||||
|
nodeNumber = NANO_D0;
|
||||||
|
|
||||||
|
if (isDigit(connString1[connString1.length()-1]))
|
||||||
|
{
|
||||||
|
|
||||||
|
nodeNumber += connString1.toInt();
|
||||||
|
|
||||||
|
} else if (connString1.equals("5V"))
|
||||||
|
{
|
||||||
|
nodeNumber = SUPPLY_5V;
|
||||||
|
} else if (connString1.equalsIgnoreCase("AREF"))
|
||||||
|
{
|
||||||
|
|
||||||
|
nodeNumber = NANO_AREF;
|
||||||
|
} else if (connString1.equalsIgnoreCase("GND"))
|
||||||
|
{
|
||||||
|
nodeNumber = GND;
|
||||||
|
} else if (connString1.equalsIgnoreCase("RESET"))
|
||||||
|
{
|
||||||
|
|
||||||
|
nodeNumber = NANO_RESET;
|
||||||
|
} else if (connString1.equalsIgnoreCase("3.3V"))
|
||||||
|
{
|
||||||
|
nodeNumber = SUPPLY_3V3;
|
||||||
|
} else if (connString1.startsWith ("A"))
|
||||||
|
{
|
||||||
|
nodeNumber = NANO_A0;
|
||||||
|
nodeNumber += connString1.toInt();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
} else if (connString1.startsWith("vcc1:"))
|
||||||
|
{
|
||||||
|
//Serial.print("vcc1\t");
|
||||||
|
nodeNumber = SUPPLY_5V;
|
||||||
|
|
||||||
|
}else if (connString1.startsWith("vcc2:"))
|
||||||
|
{
|
||||||
|
//Serial.print("vcc2\t");
|
||||||
|
nodeNumber = SUPPLY_3V3;
|
||||||
|
|
||||||
|
} else if (connString1.startsWith("gnd1:"))
|
||||||
|
{
|
||||||
|
//Serial.print("gnd1\t");
|
||||||
|
nodeNumber = GND;
|
||||||
|
} else if (connString1.startsWith("gnd2:"))
|
||||||
|
{
|
||||||
|
//Serial.print("gnd2\t");
|
||||||
|
nodeNumber = GND;
|
||||||
|
} else if (connString1.startsWith("gnd3:"))
|
||||||
|
{
|
||||||
|
nodeNumber = GND;
|
||||||
|
} else {
|
||||||
|
|
||||||
|
|
||||||
|
connectionsW[i][j] = -1;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//nodeNumber += connString1.toInt();
|
||||||
|
|
||||||
|
connectionsW[i][j] = nodeNumber;
|
||||||
|
Serial.print(connectionsW[i][j]);
|
||||||
|
|
||||||
|
//connectionsW[i][0] = connString1;
|
||||||
|
|
||||||
|
Serial.print(" \t ");
|
||||||
|
|
||||||
|
//Serial.println(connString1);
|
||||||
|
|
||||||
|
//Serial.println(connString1);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void writeToNodeFile(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
LittleFS.remove("nodeFile.txt");
|
||||||
|
delay(10);
|
||||||
|
nodeFile = LittleFS.open("nodeFile.txt", "w+");
|
||||||
|
if (!nodeFile)
|
||||||
|
{
|
||||||
|
if (debugFP)
|
||||||
|
Serial.println("Failed to open nodeFile");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
if (debugFP)
|
||||||
|
Serial.println("\n\rrecreated nodeFile.txt\n\n\rloading bridges from wokwi.txt\n\r");
|
||||||
|
}
|
||||||
|
nodeFile.print("{\n\r");
|
||||||
|
for (int i = 0; i < numConnsJson; i++)
|
||||||
|
{
|
||||||
|
if (connectionsW[i][0] == "-1" && connectionsW[i][1] != "-1")
|
||||||
|
{
|
||||||
|
lightUpNode(connectionsW[i][0].toInt());
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
if (connectionsW[i][1] == "-1" && connectionsW[i][0] != "-1")
|
||||||
|
{
|
||||||
|
lightUpNode(connectionsW[i][1].toInt());
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
if (connectionsW[i][0] == connectionsW[i][1])
|
||||||
|
{
|
||||||
|
lightUpNode(connectionsW[i][0].toInt());
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
nodeFile.print(connectionsW[i][0]);
|
||||||
|
nodeFile.print("-");
|
||||||
|
nodeFile.print(connectionsW[i][1]);
|
||||||
|
nodeFile.print(",\n\r");
|
||||||
|
|
||||||
|
}
|
||||||
|
nodeFile.print("}\n\r");
|
||||||
|
|
||||||
|
Serial.println("wrote to nodeFile.txt");
|
||||||
|
|
||||||
|
Serial.println("nodeFile.txt contents:");
|
||||||
|
nodeFile.seek(0);
|
||||||
|
while (nodeFile.available())
|
||||||
|
{
|
||||||
|
Serial.write(nodeFile.read());
|
||||||
|
}
|
||||||
|
Serial.println("\n\r");
|
||||||
|
|
||||||
|
|
||||||
|
nodeFile.close();
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void openNodeFile()
|
void openNodeFile()
|
||||||
{
|
{
|
||||||
timeToFP = millis();
|
timeToFP = millis();
|
||||||
if(DEBUG_FILEPARSING == 1) debugFP = true; //yeah we're using runtime debug flags so it can be toggled from commands
|
if (DEBUG_FILEPARSING == 1)
|
||||||
else debugFP = false;
|
debugFP = true; // yeah we're using runtime debug flags so it can be toggled from commands
|
||||||
if(TIME_FILEPARSING == 1) debugFPtime = true;
|
else
|
||||||
else debugFPtime = false;
|
debugFP = false;
|
||||||
|
if (TIME_FILEPARSING == 1)
|
||||||
|
debugFPtime = true;
|
||||||
|
else
|
||||||
|
debugFPtime = false;
|
||||||
|
|
||||||
nodeFile = LittleFS.open("nodeFile.txt", "r");
|
nodeFile = LittleFS.open("nodeFile.txt", "r");
|
||||||
if (!nodeFile)
|
if (!nodeFile)
|
||||||
{
|
{
|
||||||
if(debugFP)Serial.println("Failed to open nodeFile");
|
if (debugFP)
|
||||||
|
Serial.println("Failed to open nodeFile");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
if(debugFP)Serial.println("\n\ropened nodeFile.txt\n\n\rloading bridges from file\n\r");
|
if (debugFP)
|
||||||
|
Serial.println("\n\ropened nodeFile.txt\n\n\rloading bridges from file\n\r");
|
||||||
}
|
}
|
||||||
|
|
||||||
nodeFileString.read(nodeFile);
|
nodeFileString.read(nodeFile);
|
||||||
@ -48,35 +400,43 @@ void splitStringToFields()
|
|||||||
int openBraceIndex = 0;
|
int openBraceIndex = 0;
|
||||||
int closeBraceIndex = 0;
|
int closeBraceIndex = 0;
|
||||||
|
|
||||||
if(debugFP)Serial.println("\n\rraw input file\n\r");
|
if (debugFP)
|
||||||
if(debugFP)Serial.println(nodeFileString);
|
Serial.println("\n\rraw input file\n\r");
|
||||||
if(debugFP)Serial.println("\n\rsplitting and cleaning up string\n\r");
|
if (debugFP)
|
||||||
if(debugFP)Serial.println("_");
|
Serial.println(nodeFileString);
|
||||||
openBraceIndex = nodeFileString.indexOf("{");
|
if (debugFP)
|
||||||
closeBraceIndex = nodeFileString.indexOf("}");
|
Serial.println("\n\rsplitting and cleaning up string\n\r");
|
||||||
nodeFileString.substring(bridgeString ,openBraceIndex + 1, closeBraceIndex);
|
if (debugFP)
|
||||||
bridgeString.trim();
|
Serial.println("_");
|
||||||
|
|
||||||
if(debugFP)Serial.println(bridgeString);
|
|
||||||
|
|
||||||
if(debugFP)Serial.println("^\n\r");
|
|
||||||
|
|
||||||
nodeFileString.remove(0, closeBraceIndex + 1);
|
|
||||||
nodeFileString.trim();
|
|
||||||
|
|
||||||
openBraceIndex = nodeFileString.indexOf("{");
|
openBraceIndex = nodeFileString.indexOf("{");
|
||||||
closeBraceIndex = nodeFileString.indexOf("}");
|
closeBraceIndex = nodeFileString.indexOf("}");
|
||||||
nodeFileString.substring(specialFunctionsString, openBraceIndex + 1, closeBraceIndex);
|
nodeFileString.substring(specialFunctionsString, openBraceIndex + 1, closeBraceIndex);
|
||||||
specialFunctionsString.trim();
|
specialFunctionsString.trim();
|
||||||
if(debugFP)Serial.println("_");
|
|
||||||
if(debugFP)Serial.println(specialFunctionsString);
|
if (debugFP)
|
||||||
if(debugFP)Serial.println("^\n\r");
|
Serial.println(specialFunctionsString);
|
||||||
|
|
||||||
|
if (debugFP)
|
||||||
|
Serial.println("^\n\r");
|
||||||
|
/*
|
||||||
|
nodeFileString.remove(0, closeBraceIndex + 1);
|
||||||
|
nodeFileString.trim();
|
||||||
|
|
||||||
|
openBraceIndex = nodeFileString.indexOf("{");
|
||||||
|
closeBraceIndex = nodeFileString.indexOf("}");
|
||||||
|
//nodeFileString.substring(specialFunctionsString, openBraceIndex + 1, closeBraceIndex);
|
||||||
|
specialFunctionsString.trim();
|
||||||
|
if(debugFP)Serial.println("_");
|
||||||
|
if(debugFP)Serial.println(specialFunctionsString);
|
||||||
|
if(debugFP)Serial.println("^\n\r");
|
||||||
|
*/
|
||||||
replaceSFNamesWithDefinedInts();
|
replaceSFNamesWithDefinedInts();
|
||||||
}
|
}
|
||||||
|
|
||||||
void replaceSFNamesWithDefinedInts(void)
|
void replaceSFNamesWithDefinedInts(void)
|
||||||
{
|
{
|
||||||
if(debugFP)Serial.println("replacing special function names with defined ints\n\r");
|
if (debugFP)
|
||||||
|
Serial.println("replacing special function names with defined ints\n\r");
|
||||||
specialFunctionsString.replace("GND", "100");
|
specialFunctionsString.replace("GND", "100");
|
||||||
specialFunctionsString.replace("SUPPLY_5V", "105");
|
specialFunctionsString.replace("SUPPLY_5V", "105");
|
||||||
specialFunctionsString.replace("SUPPLY_3V3", "103");
|
specialFunctionsString.replace("SUPPLY_3V3", "103");
|
||||||
@ -85,104 +445,108 @@ void replaceSFNamesWithDefinedInts(void)
|
|||||||
specialFunctionsString.replace("I_N", "109");
|
specialFunctionsString.replace("I_N", "109");
|
||||||
specialFunctionsString.replace("I_P", "108");
|
specialFunctionsString.replace("I_P", "108");
|
||||||
specialFunctionsString.replace("EMPTY_NET", "127");
|
specialFunctionsString.replace("EMPTY_NET", "127");
|
||||||
|
specialFunctionsString.replace("ADC0_5V", "110");
|
||||||
|
specialFunctionsString.replace("ADC1_5V", "111");
|
||||||
|
specialFunctionsString.replace("ADC2_5V", "112");
|
||||||
|
specialFunctionsString.replace("ADC3_8V", "113");
|
||||||
|
|
||||||
if(debugFP)Serial.println(specialFunctionsString);
|
// if(debugFP)Serial.println(specialFunctionsString);
|
||||||
if(debugFP)Serial.println("\n\n\r");
|
// if(debugFP)Serial.println("\n\n\r");
|
||||||
|
|
||||||
replaceNanoNamesWithDefinedInts();
|
replaceNanoNamesWithDefinedInts();
|
||||||
}
|
}
|
||||||
|
|
||||||
void replaceNanoNamesWithDefinedInts(void)//for dome reason Arduino's String wasn't replacing like 1 or 2 of the names, so I'm using SafeString now and it works
|
void replaceNanoNamesWithDefinedInts(void) // for dome reason Arduino's String wasn't replacing like 1 or 2 of the names, so I'm using SafeString now and it works
|
||||||
{
|
{
|
||||||
if(debugFP)Serial.println("replacing special function names with defined ints\n\r");
|
if (debugFP)
|
||||||
|
Serial.println("replacing special function names with defined ints\n\r");
|
||||||
char nanoName[5];
|
char nanoName[5];
|
||||||
|
|
||||||
|
|
||||||
itoa(NANO_D10, nanoName, 10);
|
itoa(NANO_D10, nanoName, 10);
|
||||||
specialFunctionsString.replace("D10", nanoName);
|
specialFunctionsString.replace("D10", nanoName);
|
||||||
bridgeString.replace("D10", nanoName);
|
|
||||||
itoa(NANO_D11, nanoName, 10);
|
itoa(NANO_D11, nanoName, 10);
|
||||||
specialFunctionsString.replace("D11", nanoName);
|
specialFunctionsString.replace("D11", nanoName);
|
||||||
bridgeString.replace("D11", nanoName);
|
|
||||||
itoa(NANO_D12, nanoName, 10);
|
itoa(NANO_D12, nanoName, 10);
|
||||||
specialFunctionsString.replace("D12", nanoName);
|
specialFunctionsString.replace("D12", nanoName);
|
||||||
bridgeString.replace("D12", nanoName);
|
|
||||||
itoa(NANO_D13, nanoName, 10);
|
itoa(NANO_D13, nanoName, 10);
|
||||||
specialFunctionsString.replace("D13", nanoName);
|
specialFunctionsString.replace("D13", nanoName);
|
||||||
bridgeString.replace("D13", nanoName);
|
|
||||||
itoa(NANO_D0, nanoName, 10);
|
itoa(NANO_D0, nanoName, 10);
|
||||||
specialFunctionsString.replace("D0", nanoName);
|
specialFunctionsString.replace("D0", nanoName);
|
||||||
bridgeString.replace("D0", nanoName);
|
|
||||||
itoa(NANO_D1, nanoName, 10);
|
itoa(NANO_D1, nanoName, 10);
|
||||||
specialFunctionsString.replace("D1", nanoName);
|
specialFunctionsString.replace("D1", nanoName);
|
||||||
bridgeString.replace("D1", nanoName);
|
|
||||||
itoa(NANO_D2, nanoName, 10);
|
itoa(NANO_D2, nanoName, 10);
|
||||||
specialFunctionsString.replace("D2", nanoName);
|
specialFunctionsString.replace("D2", nanoName);
|
||||||
bridgeString.replace("D2", nanoName);
|
|
||||||
itoa(NANO_D3, nanoName, 10);
|
itoa(NANO_D3, nanoName, 10);
|
||||||
specialFunctionsString.replace("D3", nanoName);
|
specialFunctionsString.replace("D3", nanoName);
|
||||||
bridgeString.replace("D3", nanoName);
|
|
||||||
itoa(NANO_D4, nanoName, 10);
|
itoa(NANO_D4, nanoName, 10);
|
||||||
specialFunctionsString.replace("D4", nanoName);
|
specialFunctionsString.replace("D4", nanoName);
|
||||||
bridgeString.replace("D4", nanoName);
|
|
||||||
itoa(NANO_D5, nanoName, 10);
|
itoa(NANO_D5, nanoName, 10);
|
||||||
specialFunctionsString.replace("D5", nanoName);
|
specialFunctionsString.replace("D5", nanoName);
|
||||||
bridgeString.replace("D5", nanoName);
|
|
||||||
itoa(NANO_D6, nanoName, 10);
|
itoa(NANO_D6, nanoName, 10);
|
||||||
specialFunctionsString.replace("D6", nanoName);
|
specialFunctionsString.replace("D6", nanoName);
|
||||||
bridgeString.replace("D6", nanoName);
|
|
||||||
itoa(NANO_D7, nanoName, 10);
|
itoa(NANO_D7, nanoName, 10);
|
||||||
specialFunctionsString.replace("D7", nanoName);
|
specialFunctionsString.replace("D7", nanoName);
|
||||||
bridgeString.replace("D7", nanoName);
|
|
||||||
itoa(NANO_D8, nanoName, 10);
|
itoa(NANO_D8, nanoName, 10);
|
||||||
specialFunctionsString.replace("D8", nanoName);
|
specialFunctionsString.replace("D8", nanoName);
|
||||||
bridgeString.replace("D8", nanoName);
|
|
||||||
itoa(NANO_D9, nanoName, 10);
|
itoa(NANO_D9, nanoName, 10);
|
||||||
specialFunctionsString.replace("D9", nanoName);
|
specialFunctionsString.replace("D9", nanoName);
|
||||||
bridgeString.replace("D9", nanoName);
|
|
||||||
itoa(NANO_RESET, nanoName, 10);
|
itoa(NANO_RESET, nanoName, 10);
|
||||||
specialFunctionsString.replace("RESET", nanoName);
|
specialFunctionsString.replace("RESET", nanoName);
|
||||||
bridgeString.replace("RESET", nanoName);
|
|
||||||
itoa(NANO_AREF, nanoName, 10);
|
itoa(NANO_AREF, nanoName, 10);
|
||||||
specialFunctionsString.replace("AREF", nanoName);
|
specialFunctionsString.replace("AREF", nanoName);
|
||||||
bridgeString.replace("AREF", nanoName);
|
|
||||||
itoa(NANO_A0, nanoName, 10);
|
itoa(NANO_A0, nanoName, 10);
|
||||||
specialFunctionsString.replace("A0", nanoName);
|
specialFunctionsString.replace("A0", nanoName);
|
||||||
bridgeString.replace("A0", nanoName);
|
|
||||||
itoa(NANO_A1, nanoName, 10);
|
itoa(NANO_A1, nanoName, 10);
|
||||||
specialFunctionsString.replace("A1", nanoName);
|
specialFunctionsString.replace("A1", nanoName);
|
||||||
bridgeString.replace("A1", nanoName);
|
|
||||||
itoa(NANO_A2, nanoName, 10);
|
itoa(NANO_A2, nanoName, 10);
|
||||||
specialFunctionsString.replace("A2", nanoName);
|
specialFunctionsString.replace("A2", nanoName);
|
||||||
bridgeString.replace("A2", nanoName);
|
|
||||||
itoa(NANO_A3, nanoName, 10);
|
itoa(NANO_A3, nanoName, 10);
|
||||||
specialFunctionsString.replace("A3", nanoName);
|
specialFunctionsString.replace("A3", nanoName);
|
||||||
bridgeString.replace("A3", nanoName);
|
|
||||||
itoa(NANO_A4, nanoName, 10);
|
itoa(NANO_A4, nanoName, 10);
|
||||||
specialFunctionsString.replace("A4", nanoName);
|
specialFunctionsString.replace("A4", nanoName);
|
||||||
bridgeString.replace("A4", nanoName);
|
|
||||||
itoa(NANO_A5, nanoName, 10);
|
itoa(NANO_A5, nanoName, 10);
|
||||||
specialFunctionsString.replace("A5", nanoName);
|
specialFunctionsString.replace("A5", nanoName);
|
||||||
bridgeString.replace("A5", nanoName);
|
|
||||||
itoa(NANO_A6, nanoName, 10);
|
itoa(NANO_A6, nanoName, 10);
|
||||||
specialFunctionsString.replace("A6", nanoName);
|
specialFunctionsString.replace("A6", nanoName);
|
||||||
bridgeString.replace("A6", nanoName);
|
|
||||||
itoa(NANO_A7, nanoName, 10);
|
itoa(NANO_A7, nanoName, 10);
|
||||||
specialFunctionsString.replace("A7", nanoName);
|
specialFunctionsString.replace("A7", nanoName);
|
||||||
bridgeString.replace("A7", nanoName);
|
|
||||||
|
|
||||||
|
// if(debugFP)Serial.println(bridgeString);
|
||||||
|
if (debugFP)
|
||||||
|
Serial.println(specialFunctionsString);
|
||||||
|
if (debugFP)
|
||||||
|
Serial.println("\n\n\r");
|
||||||
|
|
||||||
if(debugFP)Serial.println(bridgeString);
|
parseStringToBridges();
|
||||||
if(debugFP)Serial.println(specialFunctionsString);
|
|
||||||
if(debugFP)Serial.println("\n\n\r");
|
|
||||||
|
|
||||||
parseStringToBridges();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void parseStringToBridges(void)
|
void parseStringToBridges(void)
|
||||||
{
|
{
|
||||||
|
|
||||||
int bridgeStringLength = bridgeString.length() - 1;
|
// int bridgeStringLength = bridgeString.length() - 1;
|
||||||
|
|
||||||
int specialFunctionsStringLength = specialFunctionsString.length() - 1;
|
int specialFunctionsStringLength = specialFunctionsString.length() - 1;
|
||||||
|
|
||||||
@ -192,36 +556,17 @@ void parseStringToBridges(void)
|
|||||||
newBridgeLength = 0;
|
newBridgeLength = 0;
|
||||||
newBridgeIndex = 0;
|
newBridgeIndex = 0;
|
||||||
|
|
||||||
if(debugFP)Serial.println("parsing bridges into array\n\r");
|
if (debugFP)
|
||||||
|
Serial.println("parsing bridges into array\n\r");
|
||||||
|
|
||||||
for (int i = 0; i <= specialFunctionsStringLength; i += readLength)
|
for (int i = 0; i <= specialFunctionsStringLength; i += readLength)
|
||||||
{
|
{
|
||||||
|
|
||||||
sscanf(specialFunctionsString.c_str(), "%i-%i,\n\r%n", &path[newBridgeIndex].node1, &path[newBridgeIndex].node2, &readLength);
|
sscanf(specialFunctionsString.c_str(), "%i-%i,\n\r%n", &path[newBridgeIndex].node1, &path[newBridgeIndex].node2, &readLength);
|
||||||
specialFunctionsString.remove(0, readLength);
|
specialFunctionsString.remove(0, readLength);
|
||||||
|
|
||||||
readTotal -= readLength;
|
readTotal -= readLength;
|
||||||
|
|
||||||
// if(debugFP)Serial.print(newBridge[newBridgeIndex][0]);
|
|
||||||
// if(debugFP)Serial.print("-");
|
|
||||||
// if(debugFP)Serial.println(newBridge[newBridgeIndex][1]);
|
|
||||||
|
|
||||||
newBridgeLength++;
|
|
||||||
newBridgeIndex++;
|
|
||||||
|
|
||||||
// delay(500);
|
|
||||||
}
|
|
||||||
|
|
||||||
readTotal = bridgeStringLength;
|
|
||||||
|
|
||||||
for (int i = 0; i <= bridgeStringLength; i += readLength)
|
|
||||||
{
|
|
||||||
|
|
||||||
sscanf(bridgeString.c_str(), "%i-%i,\n\r%n", &path[newBridgeIndex].node1, &path[newBridgeIndex].node2, &readLength);
|
|
||||||
bridgeString.remove(0, readLength);
|
|
||||||
|
|
||||||
readTotal -= readLength;
|
|
||||||
|
|
||||||
// if(debugFP)Serial.print(newBridge[newBridgeIndex][0]);
|
// if(debugFP)Serial.print(newBridge[newBridgeIndex][0]);
|
||||||
// if(debugFP)Serial.print("-");
|
// if(debugFP)Serial.print("-");
|
||||||
// if(debugFP)Serial.println(newBridge[newBridgeIndex][1]);
|
// if(debugFP)Serial.println(newBridge[newBridgeIndex][1]);
|
||||||
@ -231,27 +576,51 @@ void parseStringToBridges(void)
|
|||||||
|
|
||||||
// delay(500);
|
// delay(500);
|
||||||
}
|
}
|
||||||
|
/*
|
||||||
|
readTotal = bridgeStringLength;
|
||||||
|
|
||||||
|
for (int i = 0; i <= bridgeStringLength; i += readLength)
|
||||||
|
{
|
||||||
|
|
||||||
|
sscanf(bridgeString.c_str(), "%i-%i,\n\r%n", &path[newBridgeIndex].node1, &path[newBridgeIndex].node2, &readLength);
|
||||||
|
bridgeString.remove(0, readLength);
|
||||||
|
|
||||||
|
readTotal -= readLength;
|
||||||
|
|
||||||
|
// if(debugFP)Serial.print(newBridge[newBridgeIndex][0]);
|
||||||
|
// if(debugFP)Serial.print("-");
|
||||||
|
// if(debugFP)Serial.println(newBridge[newBridgeIndex][1]);
|
||||||
|
|
||||||
|
newBridgeLength++;
|
||||||
|
newBridgeIndex++;
|
||||||
|
|
||||||
|
// delay(500);
|
||||||
|
}*/
|
||||||
newBridgeIndex = 0;
|
newBridgeIndex = 0;
|
||||||
if(debugFP) for (int i = 0; i < newBridgeLength; i++)
|
if (debugFP)
|
||||||
{
|
for (int i = 0; i < newBridgeLength; i++)
|
||||||
Serial.print("[");
|
{
|
||||||
Serial.print(path[newBridgeIndex].node1);
|
Serial.print("[");
|
||||||
Serial.print("-");
|
Serial.print(path[newBridgeIndex].node1);
|
||||||
Serial.print(path[newBridgeIndex].node2);
|
Serial.print("-");
|
||||||
Serial.print("],");
|
Serial.print(path[newBridgeIndex].node2);
|
||||||
newBridgeIndex++;
|
Serial.print("],");
|
||||||
}
|
newBridgeIndex++;
|
||||||
if(debugFP)Serial.print("\n\rbridge pairs = ");
|
}
|
||||||
if(debugFP)Serial.println(newBridgeLength);
|
if (debugFP)
|
||||||
|
Serial.print("\n\rbridge pairs = ");
|
||||||
|
if (debugFP)
|
||||||
|
Serial.println(newBridgeLength);
|
||||||
|
|
||||||
nodeFileString.clear();
|
nodeFileString.clear();
|
||||||
|
|
||||||
|
|
||||||
// if(debugFP)Serial.println(nodeFileString);
|
// if(debugFP)Serial.println(nodeFileString);
|
||||||
timeToFP = millis() - timeToFP;
|
timeToFP = millis() - timeToFP;
|
||||||
if(debugFP)Serial.print("\n\rtook ");
|
if (debugFP)
|
||||||
|
Serial.print("\n\rtook ");
|
||||||
|
|
||||||
if(debugFPtime)Serial.print(timeToFP);
|
if (debugFPtime)
|
||||||
if(debugFPtime)Serial.println("ms to open and parse file\n\r");
|
Serial.print(timeToFP);
|
||||||
|
if (debugFPtime)
|
||||||
|
Serial.println("ms to open and parse file\n\r");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -3,7 +3,9 @@
|
|||||||
|
|
||||||
|
|
||||||
//this just opens the file, takes out all the bullshit, and then populates the newBridge array
|
//this just opens the file, takes out all the bullshit, and then populates the newBridge array
|
||||||
|
void parseWokwiFileToNodeFile();
|
||||||
|
void changeWokwiDefinesToJumperless ();
|
||||||
|
void writeToNodeFile(void);
|
||||||
|
|
||||||
void openNodeFile();
|
void openNodeFile();
|
||||||
|
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
|
|
||||||
#define DEBUG_FILEPARSING 1
|
#define DEBUG_FILEPARSING 1
|
||||||
#define TIME_FILEPARSING 1
|
#define TIME_FILEPARSING 1
|
||||||
#define DEBUG_NETMANAGER 1
|
#define DEBUG_NETMANAGER 0
|
||||||
#define TIME_NETMANAGER 1
|
#define TIME_NETMANAGER 1
|
||||||
|
|
||||||
#define MAX_NETS 64
|
#define MAX_NETS 64
|
||||||
@ -40,9 +40,9 @@
|
|||||||
#define CS_K 22
|
#define CS_K 22
|
||||||
#define CS_L 23
|
#define CS_L 23
|
||||||
|
|
||||||
#define DATAPIN 19
|
//#define DATAPIN 14
|
||||||
#define RESETPIN 24
|
#define RESETPIN 24
|
||||||
#define CLKPIN 18
|
//#define CLKPIN 15
|
||||||
|
|
||||||
#define UART0_TX 0
|
#define UART0_TX 0
|
||||||
#define UART0_RX 1
|
#define UART0_RX 1
|
||||||
@ -55,10 +55,10 @@
|
|||||||
|
|
||||||
#define LED_DATA_OUT 6
|
#define LED_DATA_OUT 6
|
||||||
|
|
||||||
#define ADC0_5V 26
|
#define ADC0_PIN 26
|
||||||
#define ADC1_5V 27
|
#define ADC1_PIN 27
|
||||||
#define ADC2_5V 28
|
#define ADC2_PIN 28
|
||||||
#define ADC3_8V 29
|
#define ADC3_PIN 29
|
||||||
|
|
||||||
#define T_RAIL_POS 31
|
#define T_RAIL_POS 31
|
||||||
#define T_RAIL_NEG 0
|
#define T_RAIL_NEG 0
|
||||||
@ -170,5 +170,11 @@
|
|||||||
#define CURRENT_SENSE_PLUS 108
|
#define CURRENT_SENSE_PLUS 108
|
||||||
#define CURRENT_SENSE_MINUS 109
|
#define CURRENT_SENSE_MINUS 109
|
||||||
|
|
||||||
|
#define ADC0_5V 110
|
||||||
|
#define ADC1_5V 111
|
||||||
|
#define ADC2_5V 112
|
||||||
|
#define ADC3_8V 113
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#define EMPTY_NET 127
|
#define EMPTY_NET 127
|
@ -8,7 +8,7 @@ Adafruit_NeoPixel leds(LED_COUNT, LED_PIN, NEO_GRB + NEO_KHZ800);
|
|||||||
rgbColor netColors[MAX_NETS] = {0};
|
rgbColor netColors[MAX_NETS] = {0};
|
||||||
|
|
||||||
uint8_t saturation = 254;
|
uint8_t saturation = 254;
|
||||||
uint8_t brightness = BRIGHTNESS;
|
uint8_t brightness = 254;
|
||||||
|
|
||||||
void initLEDs(void)
|
void initLEDs(void)
|
||||||
{
|
{
|
||||||
@ -130,7 +130,7 @@ void assignNetColors(void)
|
|||||||
}
|
}
|
||||||
leds.show();
|
leds.show();
|
||||||
|
|
||||||
delay(1);
|
|
||||||
int skipSpecialColors = 0;
|
int skipSpecialColors = 0;
|
||||||
uint8_t hue = 0;
|
uint8_t hue = 0;
|
||||||
|
|
||||||
@ -194,7 +194,7 @@ void assignNetColors(void)
|
|||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
hsvColor netHsv = {hue, saturation, brightness};
|
hsvColor netHsv = {hue, saturation, 255};
|
||||||
netColors[i] = HsvToRgb(netHsv);
|
netColors[i] = HsvToRgb(netHsv);
|
||||||
|
|
||||||
// leds.setPixelColor(i, netColors[i]);
|
// leds.setPixelColor(i, netColors[i]);
|
||||||
@ -225,7 +225,9 @@ uint32_t packRgb(uint8_t r, uint8_t g, uint8_t b)
|
|||||||
return (uint32_t)r << 16 | (uint32_t)g << 8 | b;
|
return (uint32_t)r << 16 | (uint32_t)g << 8 | b;
|
||||||
}
|
}
|
||||||
|
|
||||||
void lightUpNet(int netNumber, int node, int onOff)
|
|
||||||
|
|
||||||
|
void lightUpNet(int netNumber, int node, int onOff , int brightness2)
|
||||||
{
|
{
|
||||||
|
|
||||||
if (net[netNumber].nodes[1] != 0 && net[netNumber].nodes[1] < 62)
|
if (net[netNumber].nodes[1] != 0 && net[netNumber].nodes[1] < 62)
|
||||||
@ -243,7 +245,9 @@ void lightUpNet(int netNumber, int node, int onOff)
|
|||||||
{
|
{
|
||||||
if (onOff == 1)
|
if (onOff == 1)
|
||||||
{
|
{
|
||||||
uint32_t color = packRgb(net[netNumber].color.r, net[netNumber].color.g, net[netNumber].color.b);
|
|
||||||
|
uint32_t color = packRgb((net[netNumber].color.r * brightness2) >> 8, (net[netNumber].color.g * brightness2) >> 8, (net[netNumber].color.b * brightness2) >> 8);
|
||||||
|
///Serial.println(color);
|
||||||
leds.setPixelColor(nodesToPixelMap[net[netNumber].nodes[j]], color);
|
leds.setPixelColor(nodesToPixelMap[net[netNumber].nodes[j]], color);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
@ -259,6 +263,16 @@ void lightUpNet(int netNumber, int node, int onOff)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void lightUpNode(int node)
|
||||||
|
{
|
||||||
|
|
||||||
|
leds.setPixelColor(nodesToPixelMap[node], 0xffffff);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
void showNets(void)
|
void showNets(void)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
@ -8,7 +8,7 @@
|
|||||||
|
|
||||||
#define LED_PIN 25
|
#define LED_PIN 25
|
||||||
#define LED_COUNT 160
|
#define LED_COUNT 160
|
||||||
#define BRIGHTNESS 220
|
#define BRIGHTNESS 50
|
||||||
|
|
||||||
extern Adafruit_NeoPixel leds;
|
extern Adafruit_NeoPixel leds;
|
||||||
|
|
||||||
@ -53,8 +53,8 @@ void rainbowy(int ,int, int wait);
|
|||||||
void showNets(void);
|
void showNets(void);
|
||||||
void assignNetColors (void);
|
void assignNetColors (void);
|
||||||
|
|
||||||
void lightUpNet (int netNumber, int node = -1, int onOff = 1);//-1 means all nodes (default)
|
void lightUpNet (int netNumber, int node = -1, int onOff = 1, int brightness = BRIGHTNESS);//-1 means all nodes (default)
|
||||||
|
void lightUpNode (int node);
|
||||||
hsvColor RgbToHsv(rgbColor rgb);
|
hsvColor RgbToHsv(rgbColor rgb);
|
||||||
rgbColor HsvToRgb(hsvColor hsv);
|
rgbColor HsvToRgb(hsvColor hsv);
|
||||||
|
|
||||||
|
@ -12,6 +12,11 @@ int8_t newNode2 = -1;
|
|||||||
int foundNode1Net = 0; // netNumbers where that node is, a node can only be in 1 net (except current sense, we'll deal with that separately)
|
int foundNode1Net = 0; // netNumbers where that node is, a node can only be in 1 net (except current sense, we'll deal with that separately)
|
||||||
int foundNode2Net = 0; // netNumbers where that node is, a node can only be in 1 net (except current sense, we'll deal with that separately)
|
int foundNode2Net = 0; // netNumbers where that node is, a node can only be in 1 net (except current sense, we'll deal with that separately)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
int foundNode1inSpecialNet = foundNode1Net;
|
||||||
|
int foundNode2inSpecialNet = foundNode2Net;
|
||||||
|
|
||||||
// struct pathStruct path[MAX_BRIDGES]; // node1, node2, net, chip[3], x[3], y[3]
|
// struct pathStruct path[MAX_BRIDGES]; // node1, node2, net, chip[3], x[3], y[3]
|
||||||
int newBridge[MAX_BRIDGES][3]; // node1, node2, net
|
int newBridge[MAX_BRIDGES][3]; // node1, node2, net
|
||||||
int newBridgeLength = 0;
|
int newBridgeLength = 0;
|
||||||
@ -85,8 +90,8 @@ int searchExistingNets(int node1, int node2) // search through existing nets for
|
|||||||
foundNode1Net = 0;
|
foundNode1Net = 0;
|
||||||
foundNode2Net = 0;
|
foundNode2Net = 0;
|
||||||
|
|
||||||
int foundNode1inSpecialNet = 0;
|
foundNode1inSpecialNet = node1;
|
||||||
int foundNode2inSpecialNet = 0;
|
foundNode2inSpecialNet = node2;
|
||||||
|
|
||||||
for (int i = 1; i < MAX_NETS; i++)
|
for (int i = 1; i < MAX_NETS; i++)
|
||||||
{
|
{
|
||||||
@ -232,8 +237,36 @@ void combineNets(int foundNode1Net, int foundNode2Net)
|
|||||||
int swap = 0;
|
int swap = 0;
|
||||||
if ((foundNode2Net <= 7 && foundNode1Net <= 7))
|
if ((foundNode2Net <= 7 && foundNode1Net <= 7))
|
||||||
{
|
{
|
||||||
|
for (int i = 0; i < MAX_DNI; i++)
|
||||||
|
{
|
||||||
|
for (int j = 0; j < MAX_DNI; j++)
|
||||||
|
{
|
||||||
|
if ((net[foundNode1Net].doNotIntersectNodes[i] == foundNode1Net || net[foundNode2Net].doNotIntersectNodes[j] == foundNode2Net) && (net[foundNode1Net].doNotIntersectNodes[i] != -1 && net[foundNode2Net].doNotIntersectNodes[j] != -1))
|
||||||
|
{
|
||||||
|
|
||||||
|
if (debugNM)
|
||||||
|
Serial.print("can't combine Special Nets\n\r"); // maybe have it add a bridge between them if it's allowed?
|
||||||
|
|
||||||
|
path[newBridgeIndex].net = -1;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
addNodeToNet(foundNode1Net, newNode2);
|
||||||
|
addNodeToNet(foundNode2Net, newNode1);
|
||||||
|
addBridgeToNet(foundNode1Net, newNode1, newNode2);
|
||||||
|
addBridgeToNet(foundNode2Net, newNode1, newNode2);
|
||||||
|
|
||||||
|
|
||||||
if (debugNM)
|
if (debugNM)
|
||||||
Serial.print("can't combine Special Nets, skipping\n\r"); // maybe have it add a bridge between them if it's allowed?
|
Serial.print("can't combine Special Nets\n\r"); // maybe have it add a bridge between them if it's allowed?
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
path[newBridgeIndex].net = -1;
|
path[newBridgeIndex].net = -1;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
@ -843,7 +876,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 *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[12] = {"GND", "NOT_DEFINED", "NOT_DEFINED", "3V3", "NOT_DEFINED", "5V", "DAC_0", "DAC_1", "I_POS", "I_NEG"};
|
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"};
|
||||||
|
|
||||||
const char *emptyNet[] = {"EMPTY_NET", "?"};
|
const char *emptyNet[] = {"EMPTY_NET", "?"};
|
||||||
|
|
||||||
@ -851,7 +884,7 @@ const char *definesToChar(int defined) // converts the internally used #defined
|
|||||||
{
|
{
|
||||||
return defNanoToChar[defined - 70];
|
return defNanoToChar[defined - 70];
|
||||||
}
|
}
|
||||||
else if (defined >= 100 && defined <= 110)
|
else if (defined >= 100 && defined <= ADC3_8V)
|
||||||
{
|
{
|
||||||
return defSpecialToChar[defined - 100];
|
return defSpecialToChar[defined - 100];
|
||||||
}
|
}
|
||||||
|
@ -27,7 +27,7 @@ int pathsWithCandidatesIndex = 0;
|
|||||||
unsigned long timeToSort = 0;
|
unsigned long timeToSort = 0;
|
||||||
|
|
||||||
bool debugNTCC = false;
|
bool debugNTCC = false;
|
||||||
bool debugNTCC2 = true;
|
bool debugNTCC2 = false;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
@ -1213,9 +1213,29 @@ void resolveAltPaths(void)
|
|||||||
|
|
||||||
for (int bb = 0; bb < 8; bb++) // this is a long winded way to do this but it's at least slightly readable
|
for (int bb = 0; bb < 8; bb++) // this is a long winded way to do this but it's at least slightly readable
|
||||||
{
|
{
|
||||||
|
Serial.print("! ");
|
||||||
int sfChip1 = path[i].chip[0];
|
int sfChip1 = path[i].chip[0];
|
||||||
int sfChip2 = path[i].chip[1];
|
int sfChip2 = path[i].chip[1];
|
||||||
|
|
||||||
|
if (sfChip1 == CHIP_L && sfChip2 == CHIP_L)
|
||||||
|
{
|
||||||
|
path[i].altPathNeeded = false;
|
||||||
|
|
||||||
|
|
||||||
|
path[i].x[0] = xMapForNode(path[i].node1, path[i].chip[0]);
|
||||||
|
path[i].x[1] = xMapForNode(path[i].node2, path[i].chip[1]);
|
||||||
|
path[i].y[0] = -2;
|
||||||
|
path[i].y[1] = -2;
|
||||||
|
|
||||||
|
//ch[CHIP_L].xStatus[path[i].x[0]] = path[i].net;
|
||||||
|
//ch[CHIP_L].xStatus[path[i].x[1]] = path[i].net;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
int chip1Lane = xMapForNode(sfChip1, bb);
|
int chip1Lane = xMapForNode(sfChip1, bb);
|
||||||
int chip2Lane = xMapForNode(sfChip2, bb);
|
int chip2Lane = xMapForNode(sfChip2, bb);
|
||||||
|
|
||||||
@ -1749,7 +1769,7 @@ void findStartAndEndChips(int node1, int node2, int pathIdx)
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case GND ... CURRENT_SENSE_MINUS:
|
case GND ... ADC3_8V:
|
||||||
{
|
{
|
||||||
|
|
||||||
Serial.print("special function candidate chips: ");
|
Serial.print("special function candidate chips: ");
|
||||||
@ -1914,7 +1934,7 @@ void assignPathType(int pathIndex)
|
|||||||
{
|
{
|
||||||
path[pathIndex].nodeType[0] = NANO;
|
path[pathIndex].nodeType[0] = NANO;
|
||||||
}
|
}
|
||||||
else if (path[pathIndex].node1 >= GND && path[pathIndex].node1 <= CURRENT_SENSE_MINUS)
|
else if (path[pathIndex].node1 >= GND && path[pathIndex].node1 <= ADC3_8V)
|
||||||
{
|
{
|
||||||
path[pathIndex].nodeType[0] = SF;
|
path[pathIndex].nodeType[0] = SF;
|
||||||
}
|
}
|
||||||
@ -1932,7 +1952,7 @@ void assignPathType(int pathIndex)
|
|||||||
{
|
{
|
||||||
path[pathIndex].nodeType[1] = NANO;
|
path[pathIndex].nodeType[1] = NANO;
|
||||||
}
|
}
|
||||||
else if (path[pathIndex].node2 >= GND && path[pathIndex].node2 <= CURRENT_SENSE_MINUS)
|
else if (path[pathIndex].node2 >= GND && path[pathIndex].node2 <= ADC3_8V)
|
||||||
{
|
{
|
||||||
path[pathIndex].nodeType[1] = SF;
|
path[pathIndex].nodeType[1] = SF;
|
||||||
}
|
}
|
||||||
@ -1941,6 +1961,10 @@ void assignPathType(int pathIndex)
|
|||||||
{
|
{
|
||||||
path[pathIndex].pathType = NANOtoSF;
|
path[pathIndex].pathType = NANOtoSF;
|
||||||
}
|
}
|
||||||
|
else if ((path[pathIndex].nodeType[0] == SF && path[pathIndex].nodeType[1] == SF))
|
||||||
|
{
|
||||||
|
path[pathIndex].pathType = NANOtoSF;
|
||||||
|
}
|
||||||
else if ((path[pathIndex].nodeType[0] == SF && path[pathIndex].nodeType[1] == NANO))
|
else if ((path[pathIndex].nodeType[0] == SF && path[pathIndex].nodeType[1] == NANO))
|
||||||
{
|
{
|
||||||
swapNodes(pathIndex);
|
swapNodes(pathIndex);
|
||||||
|
@ -0,0 +1,844 @@
|
|||||||
|
|
||||||
|
|
||||||
|
#include "Peripherals.h"
|
||||||
|
|
||||||
|
#include "Adafruit_INA219.h"
|
||||||
|
|
||||||
|
#include "NetManager.h"
|
||||||
|
|
||||||
|
#include "LEDs.h"
|
||||||
|
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "hardware/adc.h"
|
||||||
|
#include <stdio.h>
|
||||||
|
#include "pico/stdlib.h"
|
||||||
|
#include "hardware/gpio.h"
|
||||||
|
#include "ADCInput.h"
|
||||||
|
#include "pico/cyw43_arch.h"
|
||||||
|
|
||||||
|
#define DAC_RESOLUTION 9
|
||||||
|
|
||||||
|
uint16_t freq[3] = {1, 1, 0};
|
||||||
|
uint32_t period[3] = {0, 0, 0};
|
||||||
|
uint32_t halvePeriod[3] = {0, 0, 0};
|
||||||
|
|
||||||
|
// q = square
|
||||||
|
// s = sinus
|
||||||
|
// w = sawtooth
|
||||||
|
// t = stair
|
||||||
|
// r = random
|
||||||
|
char mode[3] = {'z', 'z', 'z'};
|
||||||
|
|
||||||
|
MCP4725 dac0_5V(0x60, &Wire);
|
||||||
|
MCP4725 dac1_8V(0x63, &Wire);
|
||||||
|
INA219 INA0(0x40);
|
||||||
|
INA219 INA1(0x41);
|
||||||
|
|
||||||
|
uint16_t count;
|
||||||
|
uint32_t lastTime = 0;
|
||||||
|
|
||||||
|
// LOOKUP TABLE SINE
|
||||||
|
uint16_t sine0[360];
|
||||||
|
uint16_t sine1[360];
|
||||||
|
|
||||||
|
//ADCInput adc(A3);
|
||||||
|
|
||||||
|
|
||||||
|
void initADC(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
|
||||||
|
/// adc.setBuffers(1,64);
|
||||||
|
// adc.setFrequency(1000);
|
||||||
|
//adc.setPins(ADC3_PIN);
|
||||||
|
//adc.begin();
|
||||||
|
/*
|
||||||
|
adc_init();
|
||||||
|
adc_gpio_init(ADC0_PIN);
|
||||||
|
adc_init();
|
||||||
|
adc_gpio_init(ADC1_PIN);
|
||||||
|
adc_init();
|
||||||
|
adc_gpio_init(ADC2_PIN);
|
||||||
|
*/
|
||||||
|
//adc_init();
|
||||||
|
//adc_gpio_init(29);
|
||||||
|
//adc_set_round_robin(0x1E);
|
||||||
|
//adc_select_input(3);
|
||||||
|
|
||||||
|
//adc_run(1);
|
||||||
|
|
||||||
|
pinMode(ADC0_PIN, INPUT);
|
||||||
|
pinMode(ADC1_PIN, INPUT);
|
||||||
|
pinMode(ADC2_PIN, INPUT);
|
||||||
|
pinMode(ADC3_PIN, INPUT);
|
||||||
|
|
||||||
|
gpio_set_function(ADC3_PIN, GPIO_FUNC_NULL);
|
||||||
|
adc_gpio_init(ADC3_PIN);
|
||||||
|
adc_select_input(3);
|
||||||
|
|
||||||
|
adc_fifo_setup(true, false, 0, false, false);
|
||||||
|
adc_run(true);
|
||||||
|
analogReadResolution(12);
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void initDAC(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
dac1_8V.begin(4, 5);
|
||||||
|
dac0_5V.begin(4, 5);
|
||||||
|
|
||||||
|
Wire.begin();
|
||||||
|
|
||||||
|
dac0_5V.setValue(0);
|
||||||
|
dac1_8V.setValue(2047);
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void initINA219(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
// delay(3000);
|
||||||
|
Serial.println(__FILE__);
|
||||||
|
Serial.print("INA219_LIB_VERSION: ");
|
||||||
|
Serial.println(INA219_LIB_VERSION);
|
||||||
|
|
||||||
|
Wire.begin();
|
||||||
|
if (!INA0.begin() || !INA1.begin())
|
||||||
|
{
|
||||||
|
Serial.println("Failed to find INA219 chip");
|
||||||
|
}
|
||||||
|
|
||||||
|
// INA.setMaxCurrentShunt(1, 0.002);
|
||||||
|
// delay(1000);
|
||||||
|
// INA.setMaxCurrentShunt(2.5, 0.002);
|
||||||
|
// delay(1000);
|
||||||
|
INA0.setMaxCurrentShunt(1, 2);
|
||||||
|
INA1.setMaxCurrentShunt(1, 2);
|
||||||
|
|
||||||
|
// INA.setMaxCurrentShunt(7.5, 0.002);
|
||||||
|
// delay(1000);
|
||||||
|
// INA.setMaxCurrentShunt(10, 0.002);
|
||||||
|
// delay(1000);
|
||||||
|
// INA.setMaxCurrentShunt(15, 0.002);
|
||||||
|
// delay(1000);
|
||||||
|
// INA.setMaxCurrentShunt(20, 0.002);
|
||||||
|
// delay(10000);
|
||||||
|
|
||||||
|
Serial.println(INA0.setBusVoltageRange(16));
|
||||||
|
Serial.println(INA1.setBusVoltageRange(16));
|
||||||
|
}
|
||||||
|
|
||||||
|
void dacSine(int resolution)
|
||||||
|
{
|
||||||
|
uint16_t i;
|
||||||
|
switch (resolution)
|
||||||
|
{
|
||||||
|
case 0 ... 5:
|
||||||
|
for (i = 0; i < 32; i++)
|
||||||
|
{
|
||||||
|
dac1_8V.setValue(DACLookup_FullSine_5Bit[i]);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 6:
|
||||||
|
for (i = 0; i < 64; i++)
|
||||||
|
{
|
||||||
|
dac1_8V.setValue(DACLookup_FullSine_6Bit[i]);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 7:
|
||||||
|
for (i = 0; i < 128; i++)
|
||||||
|
{
|
||||||
|
dac1_8V.setValue(DACLookup_FullSine_7Bit[i]);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 8:
|
||||||
|
for (i = 0; i < 256; i++)
|
||||||
|
{
|
||||||
|
dac1_8V.setValue(DACLookup_FullSine_8Bit[i]);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 9 ... 12:
|
||||||
|
for (i = 0; i < 512; i++)
|
||||||
|
{
|
||||||
|
dac1_8V.setValue(DACLookup_FullSine_9Bit[i]);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void setDac0_5V(float voltage)
|
||||||
|
{
|
||||||
|
uint16_t value = voltage * 819;
|
||||||
|
// float vPerBit = 5 / 4096;
|
||||||
|
|
||||||
|
// uint32_t voltage = value * vPerBit;
|
||||||
|
|
||||||
|
Serial.print("dac0_5V voltage: ");
|
||||||
|
Serial.print(voltage);
|
||||||
|
Serial.print("\tvalue: ");
|
||||||
|
|
||||||
|
Serial.println(value);
|
||||||
|
|
||||||
|
dac0_5V.setValue(value);
|
||||||
|
|
||||||
|
// if (dac1_8V.setValue(value, 100000) == false)
|
||||||
|
//{
|
||||||
|
// Serial.println("dac1_8V.setValue() failed");
|
||||||
|
// }
|
||||||
|
}
|
||||||
|
|
||||||
|
void setDac1_8V(float voltage)
|
||||||
|
{
|
||||||
|
|
||||||
|
uint16_t value = voltage * 276;
|
||||||
|
// float vPerBit = 5 / 4096;
|
||||||
|
if (value >= 4095)
|
||||||
|
{
|
||||||
|
value = 4095;
|
||||||
|
}
|
||||||
|
|
||||||
|
// uint32_t voltage = value * vPerBit;
|
||||||
|
|
||||||
|
Serial.print("dac1 +-8V voltage: ");
|
||||||
|
Serial.print(voltage / 2);
|
||||||
|
Serial.print("\tvalue: ");
|
||||||
|
|
||||||
|
Serial.println(value);
|
||||||
|
|
||||||
|
dac1_8V.setValue(value);
|
||||||
|
|
||||||
|
// if (dac1_8V.setValue(value, 100000) == false)
|
||||||
|
//{
|
||||||
|
// Serial.println("dac1_8V.setValue() failed");
|
||||||
|
// }
|
||||||
|
}
|
||||||
|
|
||||||
|
void refillTable(int amplitude, int offset, int dac)
|
||||||
|
{
|
||||||
|
//int offsetCorr = 0;
|
||||||
|
if (dac == 0)
|
||||||
|
{
|
||||||
|
offset = amplitude / 2;
|
||||||
|
}
|
||||||
|
|
||||||
|
for (int i = 0; i < 360; i++)
|
||||||
|
{
|
||||||
|
if (dac == 0)
|
||||||
|
{
|
||||||
|
sine0[i] = offset + round(amplitude / 2 * sin(i * PI / 180));
|
||||||
|
}
|
||||||
|
else if (dac == 1)
|
||||||
|
{
|
||||||
|
sine1[i] = offset + round(amplitude / 2 * sin(i * PI / 180));
|
||||||
|
}
|
||||||
|
else if (dac == 2)
|
||||||
|
{
|
||||||
|
sine0[i] = offset + round(amplitude / 2 * sin(i * PI / 180));
|
||||||
|
sine1[i] = offset + round(amplitude / 2 * sin(i * PI / 180));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
void GetAdc29Status(int i)
|
||||||
|
{
|
||||||
|
gpio_function gpio29Function = gpio_get_function(29);
|
||||||
|
Serial.print("GPIO29 func: ");
|
||||||
|
Serial.println(gpio29Function);
|
||||||
|
|
||||||
|
bool pd = gpio_is_pulled_down(29);
|
||||||
|
Serial.print("GPIO29 pd: ");
|
||||||
|
Serial.println(pd);
|
||||||
|
|
||||||
|
bool h = gpio_is_input_hysteresis_enabled(29);
|
||||||
|
Serial.print("GPIO29 h: ");
|
||||||
|
Serial.println(h);
|
||||||
|
|
||||||
|
gpio_slew_rate slew = gpio_get_slew_rate(29);
|
||||||
|
Serial.print("GPIO29 slew: ");
|
||||||
|
Serial.println(slew);
|
||||||
|
|
||||||
|
gpio_drive_strength drive = gpio_get_drive_strength(29);
|
||||||
|
Serial.print("GPIO29 drive: ");
|
||||||
|
Serial.println(drive);
|
||||||
|
|
||||||
|
int irqmask = gpio_get_irq_event_mask(29);
|
||||||
|
Serial.print("GPIO29 irqmask: ");
|
||||||
|
Serial.println(irqmask);
|
||||||
|
|
||||||
|
bool out = gpio_is_dir_out(29);
|
||||||
|
Serial.print("GPIO29 out: ");
|
||||||
|
Serial.println(out);
|
||||||
|
Serial.printf("(%i) GPIO29 func: %i, pd: %i, h: %i, slew: %i, drive: %i, irqmask: %i, out: %i\n",i, gpio29Function, pd, h, slew, drive, irqmask, out);
|
||||||
|
}
|
||||||
|
|
||||||
|
float readAdc(int channel, int samples)
|
||||||
|
{
|
||||||
|
int adcReadingAverage = 0;
|
||||||
|
for (int i = 0; i < 20; i++)
|
||||||
|
{
|
||||||
|
adcReadingAverage += analogRead(28);
|
||||||
|
delay(5);
|
||||||
|
}
|
||||||
|
|
||||||
|
int adc3Reading = adcReadingAverage/20;
|
||||||
|
Serial.print(adc3Reading);
|
||||||
|
|
||||||
|
float adc3Voltage = (adc3Reading - 2528) / 220.0; //painstakingly measured
|
||||||
|
return adc3Voltage;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void waveGen(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
|
||||||
|
listSpecialNets();
|
||||||
|
listNets();
|
||||||
|
|
||||||
|
int activeDac = 3;
|
||||||
|
|
||||||
|
mode[0] = 's';
|
||||||
|
mode[1] = 's';
|
||||||
|
mode[2] = 's';
|
||||||
|
int dacOn[3] = {0, 0, 0};
|
||||||
|
int amplitude[3] = {4095, 4140, 0};
|
||||||
|
int offset[3] = {1, 1932, 2047};
|
||||||
|
int calib[3] = {-10, 100, 0};
|
||||||
|
|
||||||
|
|
||||||
|
refillTable(amplitude[0], offset[0] + calib[0], 0);
|
||||||
|
refillTable(amplitude[1], offset[1] + calib[1], 1);
|
||||||
|
|
||||||
|
dac0_5V.setValue(1);
|
||||||
|
dac1_8V.setValue(offset[1] + calib[1]);
|
||||||
|
|
||||||
|
Serial.println("\n\r\t\t\t\t waveGen\t\n\n\r\toptions\t\t\twaves\t\t\tadjust frequency\n\r");
|
||||||
|
Serial.println("\t5/0 = dac 0 0-5V (togg)\tq = square\t\t+ = frequency++\n\r");
|
||||||
|
Serial.println("\t8/1 = dac 1 +-8V (togg)\ts = sine\t\t- = frequency--\n\r");
|
||||||
|
Serial.println("\ta = set amplitude (p-p)\tw = sawtooth\t\t* = frequency*2\n\r");
|
||||||
|
Serial.println("\to = set offset\t\tt = triangle\t\t/ = frequency/2\n\r");
|
||||||
|
Serial.println("\tv = voltage\t\tr = random\t\t \n\r");
|
||||||
|
Serial.println("\th = show this menu\t\t\t \n\r");
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
period[activeDac] = 1e6 / freq[activeDac];
|
||||||
|
halvePeriod[activeDac] = period[activeDac] / 2;
|
||||||
|
int chars = 0;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
chars = 0;
|
||||||
|
while (1)
|
||||||
|
{
|
||||||
|
yield();
|
||||||
|
uint32_t now = micros();
|
||||||
|
|
||||||
|
count++;
|
||||||
|
|
||||||
|
|
||||||
|
//float adc3Voltage = (adc3Reading - 2528) / 220.0; //painstakingly measured
|
||||||
|
//float adc0Voltage = ((adc0Reading) / 400.0) - 0.69; //- 0.93; //painstakingly measured
|
||||||
|
if (now - lastTime > 100000)
|
||||||
|
{
|
||||||
|
|
||||||
|
//int adc0Reading = analogRead(26);
|
||||||
|
int adc0Reading = INA1.getBusVoltage_mV();;
|
||||||
|
adc0Reading = abs(adc0Reading );
|
||||||
|
|
||||||
|
for (int i = 0; i < chars; i++)
|
||||||
|
{
|
||||||
|
Serial.print("\b");
|
||||||
|
}
|
||||||
|
chars = 0;
|
||||||
|
chars = 0;
|
||||||
|
|
||||||
|
chars += Serial.print(adc0Reading);
|
||||||
|
int brightness1 = map(adc0Reading, 0, 5000, 0, 254);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
lightUpNet(4, -1, 1, brightness1);
|
||||||
|
|
||||||
|
|
||||||
|
lastTime = now;
|
||||||
|
// Serial.println(count); // show # updates per 0.1 second
|
||||||
|
count = 0;
|
||||||
|
if (Serial.available())
|
||||||
|
{
|
||||||
|
int c = Serial.read();
|
||||||
|
switch (c)
|
||||||
|
{
|
||||||
|
case '+':
|
||||||
|
freq[activeDac]++;
|
||||||
|
break;
|
||||||
|
case '-':
|
||||||
|
freq[activeDac]--;
|
||||||
|
break;
|
||||||
|
case '*':
|
||||||
|
freq[activeDac] *= 2;
|
||||||
|
break;
|
||||||
|
case '/':
|
||||||
|
freq[activeDac] /= 2;
|
||||||
|
break;
|
||||||
|
case '8':
|
||||||
|
if (activeDac == 0)
|
||||||
|
{
|
||||||
|
dac0_5V.setValue(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (activeDac != 3)
|
||||||
|
dacOn[1] = !dacOn[1];
|
||||||
|
|
||||||
|
activeDac = 1;
|
||||||
|
|
||||||
|
if (dacOn[activeDac] == 0)
|
||||||
|
{
|
||||||
|
dac1_8V.setValue(amplitude[activeDac]);
|
||||||
|
}
|
||||||
|
|
||||||
|
break;
|
||||||
|
case '5':
|
||||||
|
if (activeDac == 1)
|
||||||
|
{
|
||||||
|
dac1_8V.setValue(amplitude[activeDac]);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (activeDac != 3)
|
||||||
|
dacOn[0] = !dacOn[0];
|
||||||
|
|
||||||
|
activeDac = 0;
|
||||||
|
if (dacOn[activeDac] == 0)
|
||||||
|
{
|
||||||
|
dac0_5V.setValue(0);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 'c':
|
||||||
|
//freq[activeDac] = 0;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 's':
|
||||||
|
{
|
||||||
|
if (mode[2] == 'v')
|
||||||
|
{
|
||||||
|
refillTable(amplitude[activeDac], offset[activeDac] + calib[1], 1);
|
||||||
|
mode[2] = 's';
|
||||||
|
}
|
||||||
|
|
||||||
|
mode[activeDac] = c;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
case 'q':
|
||||||
|
|
||||||
|
case 'w':
|
||||||
|
case 't':
|
||||||
|
case 'r':
|
||||||
|
case 'z':
|
||||||
|
case 'm':
|
||||||
|
|
||||||
|
//
|
||||||
|
mode[2] = mode[activeDac];
|
||||||
|
mode[activeDac] = c;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 'v':
|
||||||
|
case 'h':
|
||||||
|
case 'a':
|
||||||
|
case 'o':
|
||||||
|
|
||||||
|
mode[2] = mode[activeDac];
|
||||||
|
|
||||||
|
mode[activeDac] = c;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
period[activeDac] = 1e6 / freq[activeDac];
|
||||||
|
halvePeriod[activeDac] = period[activeDac] / 2;
|
||||||
|
if (activeDac == 0)
|
||||||
|
{
|
||||||
|
Serial.print("dac 0: ");
|
||||||
|
Serial.print("ampl: ");
|
||||||
|
Serial.print((float)(amplitude[activeDac]) / 819);
|
||||||
|
Serial.print("V\t");
|
||||||
|
Serial.print("offset: ");
|
||||||
|
Serial.print((float)(offset[activeDac]) / 819);
|
||||||
|
Serial.print("V\t\t");
|
||||||
|
Serial.print("mode: ");
|
||||||
|
Serial.print(mode[activeDac]);
|
||||||
|
Serial.print("\t\t");
|
||||||
|
Serial.print("freq: ");
|
||||||
|
Serial.print(freq[activeDac]);
|
||||||
|
|
||||||
|
// Serial.print("\t\n\r");
|
||||||
|
}
|
||||||
|
else if (activeDac == 1)
|
||||||
|
{
|
||||||
|
Serial.print("dac 1: ");
|
||||||
|
Serial.print("ampl: ");
|
||||||
|
Serial.print((float)(amplitude[activeDac]) / 276);
|
||||||
|
Serial.print("V\t");
|
||||||
|
Serial.print("offset: ");
|
||||||
|
Serial.print(((float)(offset[activeDac]) / 276) - 7);
|
||||||
|
Serial.print("V\t\t");
|
||||||
|
Serial.print("mode: ");
|
||||||
|
Serial.print(mode[activeDac]);
|
||||||
|
Serial.print("\t\t");
|
||||||
|
Serial.print("freq: ");
|
||||||
|
Serial.print(freq[activeDac]);
|
||||||
|
// Serial.print("\t\n\r");
|
||||||
|
} Serial.print("\tdacon");
|
||||||
|
for (int i = 0; i < 3; i++)
|
||||||
|
{
|
||||||
|
Serial.print("\t");
|
||||||
|
|
||||||
|
Serial.print(dacOn[i]);
|
||||||
|
|
||||||
|
}
|
||||||
|
Serial.println();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t t = now % period[activeDac];
|
||||||
|
// if (dacOn[activeDac] == 1 )
|
||||||
|
//{
|
||||||
|
switch (mode[activeDac])
|
||||||
|
{
|
||||||
|
case 'q':
|
||||||
|
if (t < halvePeriod[activeDac])
|
||||||
|
{
|
||||||
|
if (activeDac == 0 && dacOn[activeDac] == 1)
|
||||||
|
dac0_5V.setValue(amplitude[activeDac]);
|
||||||
|
else if (activeDac == 1 && dacOn[activeDac] == 1)
|
||||||
|
dac1_8V.setValue(amplitude[activeDac]);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
if (activeDac == 0 && dacOn[activeDac] == 1)
|
||||||
|
dac0_5V.setValue(offset[activeDac]);
|
||||||
|
else if (activeDac == 1 && dacOn[activeDac] == 1)
|
||||||
|
dac1_8V.setValue(offset[activeDac]);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 'w':
|
||||||
|
if (activeDac == 0 && dacOn[activeDac] == 1)
|
||||||
|
dac0_5V.setValue(t * amplitude[activeDac] / period[activeDac]);
|
||||||
|
else if (activeDac == 1 && dacOn[activeDac] == 1)
|
||||||
|
dac1_8V.setValue(t * amplitude[activeDac] / period[activeDac]);
|
||||||
|
break;
|
||||||
|
case 't':
|
||||||
|
if (activeDac == 0 && dacOn[activeDac] == 1)
|
||||||
|
{
|
||||||
|
|
||||||
|
if (t < halvePeriod[activeDac])
|
||||||
|
dac0_5V.setValue(t * amplitude[activeDac] / halvePeriod[activeDac]);
|
||||||
|
else
|
||||||
|
dac0_5V.setValue((period[activeDac] - t) * amplitude[activeDac] / halvePeriod[activeDac]);
|
||||||
|
}
|
||||||
|
else if (activeDac == 1 && dacOn[activeDac] == 1)
|
||||||
|
{
|
||||||
|
if (t < halvePeriod[activeDac])
|
||||||
|
dac1_8V.setValue(t * amplitude[activeDac] / halvePeriod[activeDac]);
|
||||||
|
else
|
||||||
|
dac1_8V.setValue((period[activeDac] - t) * amplitude[activeDac] / halvePeriod[activeDac]);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 'r':
|
||||||
|
if (activeDac == 0 && dacOn[activeDac] == 1)
|
||||||
|
dac0_5V.setValue(random(amplitude[activeDac]) + offset[activeDac]);
|
||||||
|
else if (activeDac == 1 && dacOn[activeDac] == 1)
|
||||||
|
{
|
||||||
|
dac1_8V.setValue(random(amplitude[activeDac]) + offset[activeDac]);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 'z': // zero
|
||||||
|
if (activeDac == 0)
|
||||||
|
dac0_5V.setValue(0);
|
||||||
|
else if (activeDac == 1)
|
||||||
|
dac1_8V.setValue(offset[activeDac]);
|
||||||
|
break;
|
||||||
|
case 'h': // high
|
||||||
|
Serial.println("\n\r\t\t\t\t waveGen\t\n\n\r\toptions\t\t\twaves\t\t\tadjust frequency\n\r");
|
||||||
|
Serial.println("\t5 = dac 0 0-5V (toggle)\tq = square\t\t+ = frequency++\n\r");
|
||||||
|
Serial.println("\t8 = dac 1 +-8V (toggle)\ts = sine\t\t- = frequency--\n\r");
|
||||||
|
Serial.println("\ta = set amplitude\tw = sawtooth\t\t* = frequency*2\n\r");
|
||||||
|
Serial.println("\to = set offset\t\tt = stair\t\t/ = frequency/2\n\r");
|
||||||
|
Serial.println("\tv = voltageGen menu\tr = random\t\t0-9 = frequency_\n\r");
|
||||||
|
Serial.println("\th = show this menu\tz = triangle\t\tc = frequency = 0\n\r");
|
||||||
|
mode[activeDac] = mode[2];
|
||||||
|
break;
|
||||||
|
case 'm': // mid
|
||||||
|
// dac1_8V.setValue(2047);
|
||||||
|
break;
|
||||||
|
case 'a':
|
||||||
|
{
|
||||||
|
float newAmplitudeF = 0;
|
||||||
|
int newAmplitude = 0;
|
||||||
|
int input = 0;
|
||||||
|
char aC = 0;
|
||||||
|
int a = 0;
|
||||||
|
if (activeDac == 0)
|
||||||
|
{
|
||||||
|
|
||||||
|
Serial.print("\n\renter amplitude (0-5): ");
|
||||||
|
while (Serial.available() == 0)
|
||||||
|
;
|
||||||
|
aC = Serial.read();
|
||||||
|
if (aC == 'a')
|
||||||
|
aC = Serial.read();
|
||||||
|
a = aC;
|
||||||
|
|
||||||
|
Serial.print(aC);
|
||||||
|
|
||||||
|
if (a >= 48 && a <= 53)
|
||||||
|
{
|
||||||
|
|
||||||
|
input = a - 48;
|
||||||
|
newAmplitude = input * 819;
|
||||||
|
Serial.print(".");
|
||||||
|
while (Serial.available() == 0)
|
||||||
|
;
|
||||||
|
a = Serial.read();
|
||||||
|
if (a >= 48 && a <= 57)
|
||||||
|
{
|
||||||
|
Serial.print((char)a);
|
||||||
|
input = a - 48;
|
||||||
|
newAmplitude += input * 81.9;
|
||||||
|
|
||||||
|
amplitude[activeDac] = newAmplitude;
|
||||||
|
Serial.print("\tamplitude: ");
|
||||||
|
Serial.print((float)(amplitude[activeDac]) / 819);
|
||||||
|
Serial.println("V");
|
||||||
|
if ((offset[activeDac] - (amplitude[activeDac] / 2)) < 10 || ((amplitude[activeDac] / 2) - offset[activeDac]) < 10)
|
||||||
|
{
|
||||||
|
offset[activeDac] = (amplitude[activeDac] / 2) - 1;
|
||||||
|
}
|
||||||
|
{
|
||||||
|
offset[activeDac] = (amplitude[activeDac] / 2) - 2;
|
||||||
|
}
|
||||||
|
refillTable(amplitude[activeDac], offset[activeDac], 0);
|
||||||
|
|
||||||
|
mode[activeDac] = mode[2];
|
||||||
|
mode[2] = '0';
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if (activeDac == 1)
|
||||||
|
{
|
||||||
|
|
||||||
|
Serial.print("\n\renter peak amplitude (0-7.5): ");
|
||||||
|
while (Serial.available() == 0)
|
||||||
|
;
|
||||||
|
aC = Serial.read();
|
||||||
|
if (aC == 'a')
|
||||||
|
aC = Serial.read();
|
||||||
|
a = aC;
|
||||||
|
|
||||||
|
Serial.print(aC);
|
||||||
|
|
||||||
|
if (a >= 48 && a <= 55)
|
||||||
|
{
|
||||||
|
|
||||||
|
input = a - 48;
|
||||||
|
newAmplitude = input * 276;
|
||||||
|
Serial.print(".");
|
||||||
|
while (Serial.available() == 0)
|
||||||
|
;
|
||||||
|
a = Serial.read();
|
||||||
|
|
||||||
|
if (a == '.')
|
||||||
|
{
|
||||||
|
while (Serial.available() == 0)
|
||||||
|
;
|
||||||
|
a = Serial.read();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (a >= 48 && a <= 57)
|
||||||
|
{
|
||||||
|
Serial.print((char)a);
|
||||||
|
input = a - 48;
|
||||||
|
newAmplitude += input * 27.6;
|
||||||
|
newAmplitude *= 2;
|
||||||
|
|
||||||
|
amplitude[activeDac] = newAmplitude;
|
||||||
|
Serial.print("\tamplitude: ");
|
||||||
|
Serial.print((amplitude[activeDac]));
|
||||||
|
Serial.println(" ");
|
||||||
|
Serial.print((float)(amplitude[activeDac]) / 276);
|
||||||
|
Serial.println("V");
|
||||||
|
|
||||||
|
refillTable(amplitude[activeDac], offset[activeDac] + calib[1], 1);
|
||||||
|
|
||||||
|
mode[activeDac] = mode[2];
|
||||||
|
mode[2] = '0';
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
case 'o':
|
||||||
|
{
|
||||||
|
|
||||||
|
int newOffset = 0;
|
||||||
|
int input = 0;
|
||||||
|
char aC = 0;
|
||||||
|
int a = 0;
|
||||||
|
if (activeDac == 0)
|
||||||
|
{
|
||||||
|
|
||||||
|
Serial.print("\n\renter offset (0-5): ");
|
||||||
|
while (Serial.available() == 0)
|
||||||
|
;
|
||||||
|
aC = Serial.read();
|
||||||
|
if (aC == 'a')
|
||||||
|
aC = Serial.read();
|
||||||
|
a = aC;
|
||||||
|
|
||||||
|
Serial.print(aC);
|
||||||
|
|
||||||
|
if (a >= 48 && a <= 53)
|
||||||
|
{
|
||||||
|
|
||||||
|
input = a - 48;
|
||||||
|
newOffset = input * 819;
|
||||||
|
Serial.print(".");
|
||||||
|
while (Serial.available() == 0)
|
||||||
|
;
|
||||||
|
a = Serial.read();
|
||||||
|
if (a >= 48 && a <= 57)
|
||||||
|
{
|
||||||
|
Serial.print((char)a);
|
||||||
|
input = a - 48;
|
||||||
|
newOffset += input * 81.9;
|
||||||
|
|
||||||
|
offset[activeDac] = newOffset;
|
||||||
|
Serial.print("\toffset: ");
|
||||||
|
Serial.print((float)(offset[activeDac]) / 819);
|
||||||
|
Serial.println("V");
|
||||||
|
|
||||||
|
refillTable(amplitude[activeDac], offset[activeDac], 0);
|
||||||
|
|
||||||
|
mode[activeDac] = mode[2];
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if (activeDac == 1)
|
||||||
|
{
|
||||||
|
int negative = 0;
|
||||||
|
|
||||||
|
Serial.print("\n\rEnter offset (-7 - 7): ");
|
||||||
|
while (Serial.available() == 0)
|
||||||
|
;
|
||||||
|
aC = Serial.read();
|
||||||
|
if (aC == '-')
|
||||||
|
{
|
||||||
|
Serial.print('-');
|
||||||
|
negative = 1;
|
||||||
|
while (Serial.available() == 0)
|
||||||
|
;
|
||||||
|
aC = Serial.read();
|
||||||
|
}
|
||||||
|
|
||||||
|
a = aC;
|
||||||
|
|
||||||
|
Serial.print(aC);
|
||||||
|
|
||||||
|
if (a >= 48 && a <= 55)
|
||||||
|
{
|
||||||
|
|
||||||
|
input = a - 48;
|
||||||
|
newOffset = input * 276;
|
||||||
|
|
||||||
|
if (input == '7')
|
||||||
|
{
|
||||||
|
Serial.print(".00");
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
|
||||||
|
Serial.print(".");
|
||||||
|
while (Serial.available() == 0)
|
||||||
|
;
|
||||||
|
a = Serial.read();
|
||||||
|
if (a == '.')
|
||||||
|
{
|
||||||
|
while (Serial.available() == 0)
|
||||||
|
;
|
||||||
|
a = Serial.read();
|
||||||
|
}
|
||||||
|
|
||||||
|
if (a >= 48 && a <= 57)
|
||||||
|
{
|
||||||
|
Serial.print((char)a);
|
||||||
|
input = a - 48;
|
||||||
|
newOffset += input * 27.6;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (negative == 1)
|
||||||
|
newOffset *= -1;
|
||||||
|
|
||||||
|
newOffset += (7 * 276);
|
||||||
|
|
||||||
|
offset[activeDac] = newOffset;
|
||||||
|
Serial.print("\toffset: ");
|
||||||
|
Serial.print(((float)(offset[activeDac]) / 276) - 7);
|
||||||
|
Serial.print(" ");
|
||||||
|
Serial.print(offset[activeDac]);
|
||||||
|
Serial.println("V");
|
||||||
|
|
||||||
|
refillTable(amplitude[activeDac], offset[activeDac] + calib[1], 1);
|
||||||
|
|
||||||
|
mode[activeDac] = mode[2];
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
case 'v':
|
||||||
|
{
|
||||||
|
if (activeDac == 0 && mode[2] != 'v')
|
||||||
|
{
|
||||||
|
// freq[activeDac] = 0;
|
||||||
|
setDac0_5V(amplitude[activeDac] / 819);
|
||||||
|
mode[2] = 'v';
|
||||||
|
}
|
||||||
|
else if (activeDac == 1 && mode[2] != 'v')
|
||||||
|
{
|
||||||
|
// freq[activeDac] = 0;
|
||||||
|
// refillTable(0, offset[activeDac] + calib[1], 1);
|
||||||
|
setDac1_8V(((amplitude[activeDac] + calib[1]) / 276) - ((offset[activeDac] / 276) - 7));
|
||||||
|
mode[2] = 'v';
|
||||||
|
} else if (mode[2] == 'v') {
|
||||||
|
//mode[2] = 's';
|
||||||
|
}
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
default:
|
||||||
|
case 's':
|
||||||
|
// reference
|
||||||
|
// float f = ((PI * 2) * t)/period;
|
||||||
|
// dac1_8V.setValue(2047 + 2047 * sin(f));
|
||||||
|
//
|
||||||
|
if (mode[activeDac] != 'v')
|
||||||
|
{
|
||||||
|
int idx = (360 * t) / period[activeDac];
|
||||||
|
if (activeDac == 0 && dacOn[activeDac] == 1)
|
||||||
|
dac0_5V.setValue(sine0[idx]); // lookuptable
|
||||||
|
else if (activeDac == 1 && dacOn[activeDac] == 1)
|
||||||
|
dac1_8V.setValue(sine1[idx]); // lookuptable
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
@ -0,0 +1,177 @@
|
|||||||
|
#ifndef PERIPHERALS_H
|
||||||
|
#define PERIPHERALS_H
|
||||||
|
//#include "Adafruit_MCP4725.h"
|
||||||
|
#include "MCP4725.h"
|
||||||
|
#include <Arduino.h>
|
||||||
|
#include "INA219.h"
|
||||||
|
#include "Wire.h"
|
||||||
|
|
||||||
|
|
||||||
|
void initINA219(void);
|
||||||
|
void initADC(void);
|
||||||
|
|
||||||
|
void initDAC(void);
|
||||||
|
void dacSine (int resolution = 9);
|
||||||
|
|
||||||
|
void dacTriangle (void);
|
||||||
|
|
||||||
|
void setDac0_5V(float value);
|
||||||
|
void setDac1_8V(float value);
|
||||||
|
|
||||||
|
void refillTable (int amplitude = 2047, int offset = 2047, int adc = 2);
|
||||||
|
void waveGen(void);
|
||||||
|
void GetAdc29Status(int i);
|
||||||
|
float readAdc(int channel, int samples = 10);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
const uint16_t DACLookup_FullSine_9Bit[512] =
|
||||||
|
{
|
||||||
|
2048, 2073, 2098, 2123, 2148, 2174, 2199, 2224,
|
||||||
|
2249, 2274, 2299, 2324, 2349, 2373, 2398, 2423,
|
||||||
|
2448, 2472, 2497, 2521, 2546, 2570, 2594, 2618,
|
||||||
|
2643, 2667, 2690, 2714, 2738, 2762, 2785, 2808,
|
||||||
|
2832, 2855, 2878, 2901, 2924, 2946, 2969, 2991,
|
||||||
|
3013, 3036, 3057, 3079, 3101, 3122, 3144, 3165,
|
||||||
|
3186, 3207, 3227, 3248, 3268, 3288, 3308, 3328,
|
||||||
|
3347, 3367, 3386, 3405, 3423, 3442, 3460, 3478,
|
||||||
|
3496, 3514, 3531, 3548, 3565, 3582, 3599, 3615,
|
||||||
|
3631, 3647, 3663, 3678, 3693, 3708, 3722, 3737,
|
||||||
|
3751, 3765, 3778, 3792, 3805, 3817, 3830, 3842,
|
||||||
|
3854, 3866, 3877, 3888, 3899, 3910, 3920, 3930,
|
||||||
|
3940, 3950, 3959, 3968, 3976, 3985, 3993, 4000,
|
||||||
|
4008, 4015, 4022, 4028, 4035, 4041, 4046, 4052,
|
||||||
|
4057, 4061, 4066, 4070, 4074, 4077, 4081, 4084,
|
||||||
|
4086, 4088, 4090, 4092, 4094, 4095, 4095, 4095,
|
||||||
|
4095, 4095, 4095, 4095, 4094, 4092, 4090, 4088,
|
||||||
|
4086, 4084, 4081, 4077, 4074, 4070, 4066, 4061,
|
||||||
|
4057, 4052, 4046, 4041, 4035, 4028, 4022, 4015,
|
||||||
|
4008, 4000, 3993, 3985, 3976, 3968, 3959, 3950,
|
||||||
|
3940, 3930, 3920, 3910, 3899, 3888, 3877, 3866,
|
||||||
|
3854, 3842, 3830, 3817, 3805, 3792, 3778, 3765,
|
||||||
|
3751, 3737, 3722, 3708, 3693, 3678, 3663, 3647,
|
||||||
|
3631, 3615, 3599, 3582, 3565, 3548, 3531, 3514,
|
||||||
|
3496, 3478, 3460, 3442, 3423, 3405, 3386, 3367,
|
||||||
|
3347, 3328, 3308, 3288, 3268, 3248, 3227, 3207,
|
||||||
|
3186, 3165, 3144, 3122, 3101, 3079, 3057, 3036,
|
||||||
|
3013, 2991, 2969, 2946, 2924, 2901, 2878, 2855,
|
||||||
|
2832, 2808, 2785, 2762, 2738, 2714, 2690, 2667,
|
||||||
|
2643, 2618, 2594, 2570, 2546, 2521, 2497, 2472,
|
||||||
|
2448, 2423, 2398, 2373, 2349, 2324, 2299, 2274,
|
||||||
|
2249, 2224, 2199, 2174, 2148, 2123, 2098, 2073,
|
||||||
|
2048, 2023, 1998, 1973, 1948, 1922, 1897, 1872,
|
||||||
|
1847, 1822, 1797, 1772, 1747, 1723, 1698, 1673,
|
||||||
|
1648, 1624, 1599, 1575, 1550, 1526, 1502, 1478,
|
||||||
|
1453, 1429, 1406, 1382, 1358, 1334, 1311, 1288,
|
||||||
|
1264, 1241, 1218, 1195, 1172, 1150, 1127, 1105,
|
||||||
|
1083, 1060, 1039, 1017, 995, 974, 952, 931,
|
||||||
|
910, 889, 869, 848, 828, 808, 788, 768,
|
||||||
|
749, 729, 710, 691, 673, 654, 636, 618,
|
||||||
|
600, 582, 565, 548, 531, 514, 497, 481,
|
||||||
|
465, 449, 433, 418, 403, 388, 374, 359,
|
||||||
|
345, 331, 318, 304, 291, 279, 266, 254,
|
||||||
|
242, 230, 219, 208, 197, 186, 176, 166,
|
||||||
|
156, 146, 137, 128, 120, 111, 103, 96,
|
||||||
|
88, 81, 74, 68, 61, 55, 50, 44,
|
||||||
|
39, 35, 30, 26, 22, 19, 15, 12,
|
||||||
|
10, 8, 6, 4, 2, 1, 1, 0,
|
||||||
|
0, 0, 1, 1, 2, 4, 6, 8,
|
||||||
|
10, 12, 15, 19, 22, 26, 30, 35,
|
||||||
|
39, 44, 50, 55, 61, 68, 74, 81,
|
||||||
|
88, 96, 103, 111, 120, 128, 137, 146,
|
||||||
|
156, 166, 176, 186, 197, 208, 219, 230,
|
||||||
|
242, 254, 266, 279, 291, 304, 318, 331,
|
||||||
|
345, 359, 374, 388, 403, 418, 433, 449,
|
||||||
|
465, 481, 497, 514, 531, 548, 565, 582,
|
||||||
|
600, 618, 636, 654, 673, 691, 710, 729,
|
||||||
|
749, 768, 788, 808, 828, 848, 869, 889,
|
||||||
|
910, 931, 952, 974, 995, 1017, 1039, 1060,
|
||||||
|
1083, 1105, 1127, 1150, 1172, 1195, 1218, 1241,
|
||||||
|
1264, 1288, 1311, 1334, 1358, 1382, 1406, 1429,
|
||||||
|
1453, 1478, 1502, 1526, 1550, 1575, 1599, 1624,
|
||||||
|
1648, 1673, 1698, 1723, 1747, 1772, 1797, 1822,
|
||||||
|
1847, 1872, 1897, 1922, 1948, 1973, 1998, 2023
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint16_t DACLookup_FullSine_8Bit[256] =
|
||||||
|
{
|
||||||
|
2048, 2098, 2148, 2198, 2248, 2298, 2348, 2398,
|
||||||
|
2447, 2496, 2545, 2594, 2642, 2690, 2737, 2784,
|
||||||
|
2831, 2877, 2923, 2968, 3013, 3057, 3100, 3143,
|
||||||
|
3185, 3226, 3267, 3307, 3346, 3385, 3423, 3459,
|
||||||
|
3495, 3530, 3565, 3598, 3630, 3662, 3692, 3722,
|
||||||
|
3750, 3777, 3804, 3829, 3853, 3876, 3898, 3919,
|
||||||
|
3939, 3958, 3975, 3992, 4007, 4021, 4034, 4045,
|
||||||
|
4056, 4065, 4073, 4080, 4085, 4089, 4093, 4094,
|
||||||
|
4095, 4094, 4093, 4089, 4085, 4080, 4073, 4065,
|
||||||
|
4056, 4045, 4034, 4021, 4007, 3992, 3975, 3958,
|
||||||
|
3939, 3919, 3898, 3876, 3853, 3829, 3804, 3777,
|
||||||
|
3750, 3722, 3692, 3662, 3630, 3598, 3565, 3530,
|
||||||
|
3495, 3459, 3423, 3385, 3346, 3307, 3267, 3226,
|
||||||
|
3185, 3143, 3100, 3057, 3013, 2968, 2923, 2877,
|
||||||
|
2831, 2784, 2737, 2690, 2642, 2594, 2545, 2496,
|
||||||
|
2447, 2398, 2348, 2298, 2248, 2198, 2148, 2098,
|
||||||
|
2048, 1997, 1947, 1897, 1847, 1797, 1747, 1697,
|
||||||
|
1648, 1599, 1550, 1501, 1453, 1405, 1358, 1311,
|
||||||
|
1264, 1218, 1172, 1127, 1082, 1038, 995, 952,
|
||||||
|
910, 869, 828, 788, 749, 710, 672, 636,
|
||||||
|
600, 565, 530, 497, 465, 433, 403, 373,
|
||||||
|
345, 318, 291, 266, 242, 219, 197, 176,
|
||||||
|
156, 137, 120, 103, 88, 74, 61, 50,
|
||||||
|
39, 30, 22, 15, 10, 6, 2, 1,
|
||||||
|
0, 1, 2, 6, 10, 15, 22, 30,
|
||||||
|
39, 50, 61, 74, 88, 103, 120, 137,
|
||||||
|
156, 176, 197, 219, 242, 266, 291, 318,
|
||||||
|
345, 373, 403, 433, 465, 497, 530, 565,
|
||||||
|
600, 636, 672, 710, 749, 788, 828, 869,
|
||||||
|
910, 952, 995, 1038, 1082, 1127, 1172, 1218,
|
||||||
|
1264, 1311, 1358, 1405, 1453, 1501, 1550, 1599,
|
||||||
|
1648, 1697, 1747, 1797, 1847, 1897, 1947, 1997
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint16_t DACLookup_FullSine_7Bit[128] =
|
||||||
|
{
|
||||||
|
2048, 2148, 2248, 2348, 2447, 2545, 2642, 2737,
|
||||||
|
2831, 2923, 3013, 3100, 3185, 3267, 3346, 3423,
|
||||||
|
3495, 3565, 3630, 3692, 3750, 3804, 3853, 3898,
|
||||||
|
3939, 3975, 4007, 4034, 4056, 4073, 4085, 4093,
|
||||||
|
4095, 4093, 4085, 4073, 4056, 4034, 4007, 3975,
|
||||||
|
3939, 3898, 3853, 3804, 3750, 3692, 3630, 3565,
|
||||||
|
3495, 3423, 3346, 3267, 3185, 3100, 3013, 2923,
|
||||||
|
2831, 2737, 2642, 2545, 2447, 2348, 2248, 2148,
|
||||||
|
2048, 1947, 1847, 1747, 1648, 1550, 1453, 1358,
|
||||||
|
1264, 1172, 1082, 995, 910, 828, 749, 672,
|
||||||
|
600, 530, 465, 403, 345, 291, 242, 197,
|
||||||
|
156, 120, 88, 61, 39, 22, 10, 2,
|
||||||
|
0, 2, 10, 22, 39, 61, 88, 120,
|
||||||
|
156, 197, 242, 291, 345, 403, 465, 530,
|
||||||
|
600, 672, 749, 828, 910, 995, 1082, 1172,
|
||||||
|
1264, 1358, 1453, 1550, 1648, 1747, 1847, 1947
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint16_t DACLookup_FullSine_6Bit[64] =
|
||||||
|
{
|
||||||
|
2048, 2248, 2447, 2642, 2831, 3013, 3185, 3346,
|
||||||
|
3495, 3630, 3750, 3853, 3939, 4007, 4056, 4085,
|
||||||
|
4095, 4085, 4056, 4007, 3939, 3853, 3750, 3630,
|
||||||
|
3495, 3346, 3185, 3013, 2831, 2642, 2447, 2248,
|
||||||
|
2048, 1847, 1648, 1453, 1264, 1082, 910, 749,
|
||||||
|
600, 465, 345, 242, 156, 88, 39, 10,
|
||||||
|
0, 10, 39, 88, 156, 242, 345, 465,
|
||||||
|
600, 749, 910, 1082, 1264, 1453, 1648, 1847
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint16_t DACLookup_FullSine_5Bit[32] =
|
||||||
|
{
|
||||||
|
2048, 2447, 2831, 3185, 3495, 3750, 3939, 4056,
|
||||||
|
4095, 4056, 3939, 3750, 3495, 3185, 2831, 2447,
|
||||||
|
2048, 1648, 1264, 910, 600, 345, 156, 39,
|
||||||
|
0, 39, 156, 345, 600, 910, 1264, 1648
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#endif
|
@ -7,6 +7,9 @@
|
|||||||
#include "NetsToChipConnections.h"
|
#include "NetsToChipConnections.h"
|
||||||
#include "LEDs.h"
|
#include "LEDs.h"
|
||||||
#include "CH446Q.h"
|
#include "CH446Q.h"
|
||||||
|
#include "Peripherals.h"
|
||||||
|
#include <Wire.h>
|
||||||
|
#include <Adafruit_MCP4725.h>
|
||||||
|
|
||||||
// nanoStatus nano;
|
// nanoStatus nano;
|
||||||
const char *definesToChar(int); // i really need to find a way to not need to forward declare fuctions with this setup, i hate it
|
const char *definesToChar(int); // i really need to find a way to not need to forward declare fuctions with this setup, i hate it
|
||||||
@ -16,14 +19,20 @@ const char *definesToChar(int); // i really need to find a way to not need to fo
|
|||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
|
|
||||||
initCH446Q();
|
|
||||||
|
|
||||||
|
initCH446Q();
|
||||||
|
initADC();
|
||||||
|
initDAC();
|
||||||
|
initINA219();
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
|
|
||||||
initLEDs();
|
initLEDs();
|
||||||
LittleFS.begin();
|
LittleFS.begin();
|
||||||
delay(3000);
|
//delay(3000);
|
||||||
|
//rainbowy(255,253,100);
|
||||||
|
parseWokwiFileToNodeFile();
|
||||||
openNodeFile();
|
openNodeFile();
|
||||||
|
//while(1);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -36,16 +45,25 @@ void loop()
|
|||||||
listSpecialNets();
|
listSpecialNets();
|
||||||
listNets();
|
listNets();
|
||||||
printBridgeArray();
|
printBridgeArray();
|
||||||
|
//rainbowy(255,30,100);
|
||||||
bridgesToPaths();
|
bridgesToPaths();
|
||||||
assignNetColors();
|
assignNetColors();
|
||||||
|
//showNets();
|
||||||
delay(3000);
|
|
||||||
|
//delay(3000);
|
||||||
|
sendAllPaths();
|
||||||
|
|
||||||
|
int i = 0;
|
||||||
while (1)
|
while (1)
|
||||||
{
|
{
|
||||||
|
//sendAllPaths();
|
||||||
|
|
||||||
sendAllPaths();
|
//dacSine(1);
|
||||||
|
|
||||||
delay(1200);
|
//setDac0_5V(3.3);
|
||||||
|
waveGen();
|
||||||
|
//
|
||||||
|
//dacTriangle();
|
||||||
|
//delay(1200);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
213
JumperlessNano/src/spi.pio
Normal file
213
JumperlessNano/src/spi.pio
Normal file
@ -0,0 +1,213 @@
|
|||||||
|
;I'm just compiling this with the online pioasm compiler and then pasting the compiled code into spi.pio.h
|
||||||
|
|
||||||
|
;https://wokwi.com/tools/pioasm
|
||||||
|
|
||||||
|
;this is basically spi but it sets a system IRQ on the last bit to allow the chip select pulse to happen
|
||||||
|
|
||||||
|
;Eric, remember to set the MYNAMEISERIC define to 1 if you're using the board I sent you, otherwise set it to 0
|
||||||
|
|
||||||
|
|
||||||
|
.program spi_ch446_multi_cs
|
||||||
|
.side_set 1
|
||||||
|
|
||||||
|
.wrap_target
|
||||||
|
bitloop:
|
||||||
|
|
||||||
|
out pins, 1 side 0x0 [2]
|
||||||
|
|
||||||
|
nop side 0x1 [2]
|
||||||
|
jmp x-- bitloop side 0x1
|
||||||
|
|
||||||
|
|
||||||
|
out pins, 1 side 0x1
|
||||||
|
|
||||||
|
|
||||||
|
mov x, y side 0x1
|
||||||
|
irq 0 side 0x1
|
||||||
|
wait 0 irq 0 rel side 0x1
|
||||||
|
|
||||||
|
jmp !osre bitloop side 0x0
|
||||||
|
|
||||||
|
public entry_point: ; Must set X,Y to n-2 before starting!
|
||||||
|
|
||||||
|
|
||||||
|
pull ifempty side 0x0 [1] ; Block with CSn high (minimum 2 cycles)
|
||||||
|
|
||||||
|
nop side 0x0 [1]; CSn front porch
|
||||||
|
|
||||||
|
|
||||||
|
.wrap
|
||||||
|
|
||||||
|
% c-sdk {
|
||||||
|
|
||||||
|
//#define MYNAMEISERIC 0 //on the board I sent to eric, the data and clock lines are bodged to GPIO 18 and 19. To allow for using hardware SPI
|
||||||
|
|
||||||
|
#include "hardware/gpio.h"
|
||||||
|
|
||||||
|
static inline void pio_spi_ch446_multi_cs_init(PIO pio, uint sm, uint prog_offs, uint n_bits, float clkdiv, bool cpha, bool cpol,
|
||||||
|
uint pin_sck, uint pin_mosi) {
|
||||||
|
|
||||||
|
pio_sm_config c = spi_ch446_multi_cs_program_get_default_config(prog_offs);
|
||||||
|
|
||||||
|
sm_config_set_out_pins(&c, pin_mosi, 1);
|
||||||
|
|
||||||
|
sm_config_set_set_pins(&c, pin_mosi, 1);
|
||||||
|
|
||||||
|
sm_config_set_sideset_pins(&c, pin_sck);
|
||||||
|
|
||||||
|
sm_config_set_out_shift(&c, false, true, n_bits);
|
||||||
|
|
||||||
|
sm_config_set_clkdiv(&c, clkdiv);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
pio_sm_set_consecutive_pindirs (pio, sm, pin_mosi, 2, true);
|
||||||
|
|
||||||
|
|
||||||
|
pio_gpio_init(pio, pin_mosi);
|
||||||
|
|
||||||
|
pio_gpio_init(pio, pin_sck);
|
||||||
|
//pio_set_irqn_source_enabled (pio,0,pis_sm0_tx_fifo_not_full,true);
|
||||||
|
|
||||||
|
// The reason for doing interrupt0 + sm:
|
||||||
|
// IRQ sources are enabled per irq flag. Since the irq flag being set depends on the state
|
||||||
|
// machine because of the "0 rel", we want to make sure we're enabling the correct interrupt
|
||||||
|
// source for the state machine the program is loaded into.
|
||||||
|
|
||||||
|
pio_set_irq0_source_enabled(pio, (pio_interrupt_source)(pis_interrupt0 + sm), true);
|
||||||
|
|
||||||
|
// Make sure the interrupt starts cleared. It should already be cleared, so this should
|
||||||
|
// basically be a no-op. I call it defensive programming.
|
||||||
|
|
||||||
|
pio_interrupt_clear(pio, sm);
|
||||||
|
|
||||||
|
// Build the configuration for the state machine
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//pio_set_irq0_source_enabled(pio, pis_interrupt0, true);
|
||||||
|
|
||||||
|
irq_set_enabled(PIO0_IRQ_0, true);
|
||||||
|
|
||||||
|
uint entry_point = prog_offs;
|
||||||
|
pio_sm_init(pio, sm, entry_point, &c);
|
||||||
|
pio_sm_exec(pio, sm, pio_encode_set(pio_x, n_bits - 2));
|
||||||
|
pio_sm_exec(pio, sm, pio_encode_set(pio_y, n_bits - 2));
|
||||||
|
pio_sm_set_enabled(pio, sm, true);
|
||||||
|
}
|
||||||
|
%}
|
||||||
|
/*
|
||||||
|
//this doesnt work, so instead Im using the PIO IRQ to set the CS pin
|
||||||
|
.program spi_ch446_cs_handler
|
||||||
|
|
||||||
|
;.word 0b00000000000000001
|
||||||
|
.wrap_target
|
||||||
|
|
||||||
|
|
||||||
|
setI:
|
||||||
|
set pins, 1
|
||||||
|
nop [3]
|
||||||
|
set pins, 0
|
||||||
|
jmp bitloop2
|
||||||
|
setJ:
|
||||||
|
set pins, 2
|
||||||
|
nop [3]
|
||||||
|
set pins, 0
|
||||||
|
jmp bitloop2
|
||||||
|
setK:
|
||||||
|
set pins, 4
|
||||||
|
nop [3]
|
||||||
|
set pins, 0
|
||||||
|
jmp bitloop2
|
||||||
|
setL:
|
||||||
|
set pins, 8
|
||||||
|
nop [3]
|
||||||
|
set pins, 0
|
||||||
|
jmp bitloop2
|
||||||
|
|
||||||
|
public entry_point:
|
||||||
|
bitloop2:
|
||||||
|
|
||||||
|
|
||||||
|
wait 1 irq 2
|
||||||
|
pull ifempty
|
||||||
|
irq clear 2
|
||||||
|
out pins, 8
|
||||||
|
|
||||||
|
set pins, 31
|
||||||
|
nop [3]
|
||||||
|
set pins, 0
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
jmp bitloop2
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
.wrap
|
||||||
|
|
||||||
|
% c-sdk {
|
||||||
|
#include "hardware/gpio.h"
|
||||||
|
static inline void pio_spi_ch446_cs_handler_init(PIO pio, uint smCS, uint prog_offs, float clkdiv, uint y, uint x, uint pin_cs_I, uint pin_cs_A) {
|
||||||
|
|
||||||
|
pio_sm_config c = spi_ch446_cs_handler_program_get_default_config(prog_offs);
|
||||||
|
|
||||||
|
sm_config_set_set_pins(&c, pin_cs_I, 4);
|
||||||
|
|
||||||
|
sm_config_set_out_pins(&c, pin_cs_A, 8);
|
||||||
|
|
||||||
|
|
||||||
|
sm_config_set_out_shift(&c, false, true, x);
|
||||||
|
|
||||||
|
sm_config_set_clkdiv(&c, clkdiv);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
pio_sm_set_pindirs_with_mask (pio, smCS, 1, 0b000000000111100000111111111100000);
|
||||||
|
;pio_sm_set_consecutive_pindirs (pio, smCS, pin_cs_I, 4, true);
|
||||||
|
|
||||||
|
|
||||||
|
gpio_set_outover(pin_cs_A, GPIO_OVERRIDE_INVERT);
|
||||||
|
gpio_set_outover(pin_cs_A+1, GPIO_OVERRIDE_INVERT);
|
||||||
|
gpio_set_outover(pin_cs_A+2, GPIO_OVERRIDE_INVERT);
|
||||||
|
gpio_set_outover(pin_cs_A+3, GPIO_OVERRIDE_INVERT);
|
||||||
|
gpio_set_outover(pin_cs_A+4, GPIO_OVERRIDE_INVERT);
|
||||||
|
gpio_set_outover(pin_cs_A+5, GPIO_OVERRIDE_INVERT);
|
||||||
|
gpio_set_outover(pin_cs_A+6, GPIO_OVERRIDE_INVERT);
|
||||||
|
gpio_set_outover(pin_cs_A+7, GPIO_OVERRIDE_INVERT);
|
||||||
|
|
||||||
|
pio_gpio_init(pio, pin_cs_A);
|
||||||
|
pio_gpio_init(pio, pin_cs_A + 1);
|
||||||
|
pio_gpio_init(pio, pin_cs_A + 2);
|
||||||
|
pio_gpio_init(pio, pin_cs_A + 3);
|
||||||
|
pio_gpio_init(pio, pin_cs_A + 4);
|
||||||
|
pio_gpio_init(pio, pin_cs_A + 5);
|
||||||
|
pio_gpio_init(pio, pin_cs_A + 6);
|
||||||
|
pio_gpio_init(pio, pin_cs_A + 7);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
pio_gpio_init(pio, pin_cs_I);
|
||||||
|
pio_gpio_init(pio, pin_cs_I + 1);
|
||||||
|
pio_gpio_init(pio, pin_cs_I + 2);
|
||||||
|
pio_gpio_init(pio, pin_cs_I + 3);
|
||||||
|
|
||||||
|
pio_set_irq0_source_enabled(pio, pis_interrupt2, true);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
uint entry_point = prog_offs;
|
||||||
|
pio_sm_init(pio, smCS, entry_point, &c);
|
||||||
|
pio_sm_exec(pio, smCS, pio_encode_set(pio_x, x));
|
||||||
|
pio_sm_exec(pio, smCS, pio_encode_set(pio_y, y));
|
||||||
|
pio_sm_set_enabled(pio, smCS, true);
|
||||||
|
}
|
||||||
|
%}
|
||||||
|
*/
|
@ -8,194 +8,6 @@
|
|||||||
#include "hardware/pio.h"
|
#include "hardware/pio.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// --------- //
|
|
||||||
// spi_cpha0 //
|
|
||||||
// --------- //
|
|
||||||
|
|
||||||
#define spi_cpha0_wrap_target 0
|
|
||||||
#define spi_cpha0_wrap 1
|
|
||||||
|
|
||||||
static const uint16_t spi_cpha0_program_instructions[] = {
|
|
||||||
// .wrap_target
|
|
||||||
0x6101, // 0: out pins, 1 side 0 [1]
|
|
||||||
0x5101, // 1: in pins, 1 side 1 [1]
|
|
||||||
// .wrap
|
|
||||||
};
|
|
||||||
|
|
||||||
#if !PICO_NO_HARDWARE
|
|
||||||
static const struct pio_program spi_cpha0_program = {
|
|
||||||
.instructions = spi_cpha0_program_instructions,
|
|
||||||
.length = 2,
|
|
||||||
.origin = -1,
|
|
||||||
};
|
|
||||||
|
|
||||||
static inline pio_sm_config spi_cpha0_program_get_default_config(uint offset) {
|
|
||||||
pio_sm_config c = pio_get_default_sm_config();
|
|
||||||
sm_config_set_wrap(&c, offset + spi_cpha0_wrap_target, offset + spi_cpha0_wrap);
|
|
||||||
sm_config_set_sideset(&c, 1, false, false);
|
|
||||||
return c;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// --------- //
|
|
||||||
// spi_cpha1 //
|
|
||||||
// --------- //
|
|
||||||
|
|
||||||
#define spi_cpha1_wrap_target 0
|
|
||||||
#define spi_cpha1_wrap 2
|
|
||||||
|
|
||||||
static const uint16_t spi_cpha1_program_instructions[] = {
|
|
||||||
// .wrap_target
|
|
||||||
0x6021, // 0: out x, 1 side 0
|
|
||||||
0xb101, // 1: mov pins, x side 1 [1]
|
|
||||||
0x4001, // 2: in pins, 1 side 0
|
|
||||||
// .wrap
|
|
||||||
};
|
|
||||||
|
|
||||||
#if !PICO_NO_HARDWARE
|
|
||||||
static const struct pio_program spi_cpha1_program = {
|
|
||||||
.instructions = spi_cpha1_program_instructions,
|
|
||||||
.length = 3,
|
|
||||||
.origin = -1,
|
|
||||||
};
|
|
||||||
|
|
||||||
static inline pio_sm_config spi_cpha1_program_get_default_config(uint offset) {
|
|
||||||
pio_sm_config c = pio_get_default_sm_config();
|
|
||||||
sm_config_set_wrap(&c, offset + spi_cpha1_wrap_target, offset + spi_cpha1_wrap);
|
|
||||||
sm_config_set_sideset(&c, 1, false, false);
|
|
||||||
return c;
|
|
||||||
}
|
|
||||||
|
|
||||||
#include "hardware/gpio.h"
|
|
||||||
static inline void pio_spi_init(PIO pio, uint sm, uint prog_offs, uint n_bits,
|
|
||||||
float clkdiv, bool cpha, bool cpol, uint pin_sck, uint pin_mosi, uint pin_miso) {
|
|
||||||
pio_sm_config c = cpha ? spi_cpha1_program_get_default_config(prog_offs) : spi_cpha0_program_get_default_config(prog_offs);
|
|
||||||
sm_config_set_out_pins(&c, pin_mosi, 1);
|
|
||||||
sm_config_set_in_pins(&c, pin_miso);
|
|
||||||
sm_config_set_sideset_pins(&c, pin_sck);
|
|
||||||
// Only support MSB-first in this example code (shift to left, auto push/pull, threshold=nbits)
|
|
||||||
sm_config_set_out_shift(&c, false, true, n_bits);
|
|
||||||
sm_config_set_in_shift(&c, false, true, n_bits);
|
|
||||||
sm_config_set_clkdiv(&c, clkdiv);
|
|
||||||
// MOSI, SCK output are low, MISO is input
|
|
||||||
pio_sm_set_pins_with_mask(pio, sm, 0, (1u << pin_sck) | (1u << pin_mosi));
|
|
||||||
pio_sm_set_pindirs_with_mask(pio, sm, (1u << pin_sck) | (1u << pin_mosi), (1u << pin_sck) | (1u << pin_mosi) | (1u << pin_miso));
|
|
||||||
pio_gpio_init(pio, pin_mosi);
|
|
||||||
pio_gpio_init(pio, pin_miso);
|
|
||||||
pio_gpio_init(pio, pin_sck);
|
|
||||||
// The pin muxes can be configured to invert the output (among other things
|
|
||||||
// and this is a cheesy way to get CPOL=1
|
|
||||||
gpio_set_outover(pin_sck, cpol ? GPIO_OVERRIDE_INVERT : GPIO_OVERRIDE_NORMAL);
|
|
||||||
// SPI is synchronous, so bypass input synchroniser to reduce input delay.
|
|
||||||
hw_set_bits(&pio->input_sync_bypass, 1u << pin_miso);
|
|
||||||
pio_sm_init(pio, sm, prog_offs, &c);
|
|
||||||
pio_sm_set_enabled(pio, sm, true);
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// ------------ //
|
|
||||||
// spi_cpha0_cs //
|
|
||||||
// ------------ //
|
|
||||||
|
|
||||||
#define spi_cpha0_cs_wrap_target 0
|
|
||||||
#define spi_cpha0_cs_wrap 8
|
|
||||||
|
|
||||||
#define spi_cpha0_cs_offset_entry_point 8u
|
|
||||||
|
|
||||||
static const uint16_t spi_cpha0_cs_program_instructions[] = {
|
|
||||||
// .wrap_target
|
|
||||||
0x6101, // 0: out pins, 1 side 0 [1]
|
|
||||||
0x4801, // 1: in pins, 1 side 1
|
|
||||||
0x0840, // 2: jmp x--, 0 side 1
|
|
||||||
0x6001, // 3: out pins, 1 side 0
|
|
||||||
0xa022, // 4: mov x, y side 0
|
|
||||||
0x4801, // 5: in pins, 1 side 1
|
|
||||||
0x08e0, // 6: jmp !osre, 0 side 1
|
|
||||||
0xa142, // 7: nop side 0 [1]
|
|
||||||
0x91e0, // 8: pull ifempty block side 2 [1]
|
|
||||||
// .wrap
|
|
||||||
};
|
|
||||||
|
|
||||||
#if !PICO_NO_HARDWARE
|
|
||||||
static const struct pio_program spi_cpha0_cs_program = {
|
|
||||||
.instructions = spi_cpha0_cs_program_instructions,
|
|
||||||
.length = 9,
|
|
||||||
.origin = -1,
|
|
||||||
};
|
|
||||||
|
|
||||||
static inline pio_sm_config spi_cpha0_cs_program_get_default_config(uint offset) {
|
|
||||||
pio_sm_config c = pio_get_default_sm_config();
|
|
||||||
sm_config_set_wrap(&c, offset + spi_cpha0_cs_wrap_target, offset + spi_cpha0_cs_wrap);
|
|
||||||
sm_config_set_sideset(&c, 2, false, false);
|
|
||||||
return c;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// ------------ //
|
|
||||||
// spi_cpha1_cs //
|
|
||||||
// ------------ //
|
|
||||||
|
|
||||||
#define spi_cpha1_cs_wrap_target 0
|
|
||||||
#define spi_cpha1_cs_wrap 8
|
|
||||||
|
|
||||||
#define spi_cpha1_cs_offset_entry_point 7u
|
|
||||||
|
|
||||||
static const uint16_t spi_cpha1_cs_program_instructions[] = {
|
|
||||||
// .wrap_target
|
|
||||||
0x6901, // 0: out pins, 1 side 1 [1]
|
|
||||||
0x4001, // 1: in pins, 1 side 0
|
|
||||||
0x0040, // 2: jmp x--, 0 side 0
|
|
||||||
0x6801, // 3: out pins, 1 side 1
|
|
||||||
0xa822, // 4: mov x, y side 1
|
|
||||||
0x4001, // 5: in pins, 1 side 0
|
|
||||||
0x00e0, // 6: jmp !osre, 0 side 0
|
|
||||||
0x91e0, // 7: pull ifempty block side 2 [1]
|
|
||||||
0xa142, // 8: nop side 0 [1]
|
|
||||||
// .wrap
|
|
||||||
};
|
|
||||||
|
|
||||||
#if !PICO_NO_HARDWARE
|
|
||||||
static const struct pio_program spi_cpha1_cs_program = {
|
|
||||||
.instructions = spi_cpha1_cs_program_instructions,
|
|
||||||
.length = 9,
|
|
||||||
.origin = -1,
|
|
||||||
};
|
|
||||||
|
|
||||||
static inline pio_sm_config spi_cpha1_cs_program_get_default_config(uint offset) {
|
|
||||||
pio_sm_config c = pio_get_default_sm_config();
|
|
||||||
sm_config_set_wrap(&c, offset + spi_cpha1_cs_wrap_target, offset + spi_cpha1_cs_wrap);
|
|
||||||
sm_config_set_sideset(&c, 2, false, false);
|
|
||||||
return c;
|
|
||||||
}
|
|
||||||
|
|
||||||
#include "hardware/gpio.h"
|
|
||||||
static inline void pio_spi_cs_init(PIO pio, uint sm, uint prog_offs, uint n_bits, float clkdiv, bool cpha, bool cpol,
|
|
||||||
uint pin_sck, uint pin_mosi, uint pin_miso) {
|
|
||||||
pio_sm_config c = cpha ? spi_cpha1_cs_program_get_default_config(prog_offs) : spi_cpha0_cs_program_get_default_config(prog_offs);
|
|
||||||
sm_config_set_out_pins(&c, pin_mosi, 1);
|
|
||||||
sm_config_set_in_pins(&c, pin_miso);
|
|
||||||
sm_config_set_sideset_pins(&c, pin_sck);
|
|
||||||
sm_config_set_out_shift(&c, false, true, n_bits);
|
|
||||||
sm_config_set_in_shift(&c, false, true, n_bits);
|
|
||||||
sm_config_set_clkdiv(&c, clkdiv);
|
|
||||||
pio_sm_set_pins_with_mask(pio, sm, (2u << pin_sck), (3u << pin_sck) | (1u << pin_mosi));
|
|
||||||
pio_sm_set_pindirs_with_mask(pio, sm, (3u << pin_sck) | (1u << pin_mosi), (3u << pin_sck) | (1u << pin_mosi) | (1u << pin_miso));
|
|
||||||
pio_gpio_init(pio, pin_mosi);
|
|
||||||
pio_gpio_init(pio, pin_miso);
|
|
||||||
pio_gpio_init(pio, pin_sck);
|
|
||||||
pio_gpio_init(pio, pin_sck + 1);
|
|
||||||
gpio_set_outover(pin_sck, cpol ? GPIO_OVERRIDE_INVERT : GPIO_OVERRIDE_NORMAL);
|
|
||||||
hw_set_bits(&pio->input_sync_bypass, 1u << pin_miso);
|
|
||||||
uint entry_point = prog_offs + (cpha ? spi_cpha1_cs_offset_entry_point : spi_cpha0_cs_offset_entry_point);
|
|
||||||
pio_sm_init(pio, sm, entry_point, &c);
|
|
||||||
pio_sm_exec(pio, sm, pio_encode_set(pio_x, n_bits - 2));
|
|
||||||
pio_sm_exec(pio, sm, pio_encode_set(pio_y, n_bits - 2));
|
|
||||||
pio_sm_set_enabled(pio, sm, true);
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// ------------------ //
|
// ------------------ //
|
||||||
// spi_ch446_multi_cs //
|
// spi_ch446_multi_cs //
|
||||||
// ------------------ //
|
// ------------------ //
|
||||||
@ -234,6 +46,7 @@ static inline pio_sm_config spi_ch446_multi_cs_program_get_default_config(uint o
|
|||||||
return c;
|
return c;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
//#define MYNAMEISERIC 0 //on the board I sent to eric, the data and clock lines are bodged to GPIO 18 and 19. To allow for using hardware SPI
|
||||||
#include "hardware/gpio.h"
|
#include "hardware/gpio.h"
|
||||||
static inline void pio_spi_ch446_multi_cs_init(PIO pio, uint sm, uint prog_offs, uint n_bits, float clkdiv, bool cpha, bool cpol,
|
static inline void pio_spi_ch446_multi_cs_init(PIO pio, uint sm, uint prog_offs, uint n_bits, float clkdiv, bool cpha, bool cpol,
|
||||||
uint pin_sck, uint pin_mosi) {
|
uint pin_sck, uint pin_mosi) {
|
||||||
@ -243,7 +56,7 @@ static inline void pio_spi_ch446_multi_cs_init(PIO pio, uint sm, uint prog_offs,
|
|||||||
sm_config_set_sideset_pins(&c, pin_sck);
|
sm_config_set_sideset_pins(&c, pin_sck);
|
||||||
sm_config_set_out_shift(&c, false, true, n_bits);
|
sm_config_set_out_shift(&c, false, true, n_bits);
|
||||||
sm_config_set_clkdiv(&c, clkdiv);
|
sm_config_set_clkdiv(&c, clkdiv);
|
||||||
pio_sm_set_consecutive_pindirs (pio, sm, pin_sck, 2, true);
|
pio_sm_set_consecutive_pindirs (pio, sm, pin_mosi, 2, true);
|
||||||
pio_gpio_init(pio, pin_mosi);
|
pio_gpio_init(pio, pin_mosi);
|
||||||
pio_gpio_init(pio, pin_sck);
|
pio_gpio_init(pio, pin_sck);
|
||||||
//pio_set_irqn_source_enabled (pio,0,pis_sm0_tx_fifo_not_full,true);
|
//pio_set_irqn_source_enabled (pio,0,pis_sm0_tx_fifo_not_full,true);
|
||||||
|
4
JumperlessNano/wokwi.toml
Normal file
4
JumperlessNano/wokwi.toml
Normal file
@ -0,0 +1,4 @@
|
|||||||
|
[wokwi]
|
||||||
|
version = 1
|
||||||
|
firmware = '.pio/build/pico/firmware.hex'
|
||||||
|
elf = '.pio/build/pico/firmware.elf'
|
Loading…
Reference in New Issue
Block a user