mirror of
https://github.com/Architeuthis-Flux/Jumperless.git
synced 2024-11-24 07:10:11 +01:00
Bridge app now auto updates
This commit is contained in:
parent
c6ac919637
commit
06bb0e4bdf
@ -0,0 +1,24 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
|
||||||
|
<plist version="1.0">
|
||||||
|
<dict>
|
||||||
|
<key>CFBundleDisplayName</key>
|
||||||
|
<string>jumperlesswokwibridge</string>
|
||||||
|
<key>CFBundleExecutable</key>
|
||||||
|
<string>jumperlesswokwibridge</string>
|
||||||
|
<key>CFBundleIconFile</key>
|
||||||
|
<string>icon.icns</string>
|
||||||
|
<key>CFBundleIdentifier</key>
|
||||||
|
<string>jumperlesswokwibridge</string>
|
||||||
|
<key>CFBundleInfoDictionaryVersion</key>
|
||||||
|
<string>6.0</string>
|
||||||
|
<key>CFBundleName</key>
|
||||||
|
<string>jumperlesswokwibridge</string>
|
||||||
|
<key>CFBundlePackageType</key>
|
||||||
|
<string>APPL</string>
|
||||||
|
<key>CFBundleShortVersionString</key>
|
||||||
|
<string>0.0.0</string>
|
||||||
|
<key>NSHighResolutionCapable</key>
|
||||||
|
<true/>
|
||||||
|
</dict>
|
||||||
|
</plist>
|
@ -0,0 +1,4 @@
|
|||||||
|
#!/bin/bash
|
||||||
|
# This is the launcher for OSX, this way the app will be opened
|
||||||
|
# when you double click it from the apps folder
|
||||||
|
open -n /Applications/jumperlesswokwibridge.app/Contents/MacOS/jumperlesswokwibridge_cli
|
Binary file not shown.
Binary file not shown.
@ -0,0 +1,128 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
|
||||||
|
<plist version="1.0">
|
||||||
|
<dict>
|
||||||
|
<key>files</key>
|
||||||
|
<dict>
|
||||||
|
<key>Resources/icon.icns</key>
|
||||||
|
<data>
|
||||||
|
Xu4NmrrU6OurOrFICyIOVsLyKYI=
|
||||||
|
</data>
|
||||||
|
</dict>
|
||||||
|
<key>files2</key>
|
||||||
|
<dict>
|
||||||
|
<key>Resources/icon.icns</key>
|
||||||
|
<dict>
|
||||||
|
<key>hash2</key>
|
||||||
|
<data>
|
||||||
|
S1gViwZdpIU/2oQNGamS1Xyba7CNbCq3KLsni+cWmvw=
|
||||||
|
</data>
|
||||||
|
</dict>
|
||||||
|
</dict>
|
||||||
|
<key>rules</key>
|
||||||
|
<dict>
|
||||||
|
<key>^Resources/</key>
|
||||||
|
<true/>
|
||||||
|
<key>^Resources/.*\.lproj/</key>
|
||||||
|
<dict>
|
||||||
|
<key>optional</key>
|
||||||
|
<true/>
|
||||||
|
<key>weight</key>
|
||||||
|
<real>1000</real>
|
||||||
|
</dict>
|
||||||
|
<key>^Resources/.*\.lproj/locversion.plist$</key>
|
||||||
|
<dict>
|
||||||
|
<key>omit</key>
|
||||||
|
<true/>
|
||||||
|
<key>weight</key>
|
||||||
|
<real>1100</real>
|
||||||
|
</dict>
|
||||||
|
<key>^Resources/Base\.lproj/</key>
|
||||||
|
<dict>
|
||||||
|
<key>weight</key>
|
||||||
|
<real>1010</real>
|
||||||
|
</dict>
|
||||||
|
<key>^version.plist$</key>
|
||||||
|
<true/>
|
||||||
|
</dict>
|
||||||
|
<key>rules2</key>
|
||||||
|
<dict>
|
||||||
|
<key>.*\.dSYM($|/)</key>
|
||||||
|
<dict>
|
||||||
|
<key>weight</key>
|
||||||
|
<real>11</real>
|
||||||
|
</dict>
|
||||||
|
<key>^(.*/)?\.DS_Store$</key>
|
||||||
|
<dict>
|
||||||
|
<key>omit</key>
|
||||||
|
<true/>
|
||||||
|
<key>weight</key>
|
||||||
|
<real>2000</real>
|
||||||
|
</dict>
|
||||||
|
<key>^(Frameworks|SharedFrameworks|PlugIns|Plug-ins|XPCServices|Helpers|MacOS|Library/(Automator|Spotlight|LoginItems))/</key>
|
||||||
|
<dict>
|
||||||
|
<key>nested</key>
|
||||||
|
<true/>
|
||||||
|
<key>weight</key>
|
||||||
|
<real>10</real>
|
||||||
|
</dict>
|
||||||
|
<key>^.*</key>
|
||||||
|
<true/>
|
||||||
|
<key>^Info\.plist$</key>
|
||||||
|
<dict>
|
||||||
|
<key>omit</key>
|
||||||
|
<true/>
|
||||||
|
<key>weight</key>
|
||||||
|
<real>20</real>
|
||||||
|
</dict>
|
||||||
|
<key>^PkgInfo$</key>
|
||||||
|
<dict>
|
||||||
|
<key>omit</key>
|
||||||
|
<true/>
|
||||||
|
<key>weight</key>
|
||||||
|
<real>20</real>
|
||||||
|
</dict>
|
||||||
|
<key>^Resources/</key>
|
||||||
|
<dict>
|
||||||
|
<key>weight</key>
|
||||||
|
<real>20</real>
|
||||||
|
</dict>
|
||||||
|
<key>^Resources/.*\.lproj/</key>
|
||||||
|
<dict>
|
||||||
|
<key>optional</key>
|
||||||
|
<true/>
|
||||||
|
<key>weight</key>
|
||||||
|
<real>1000</real>
|
||||||
|
</dict>
|
||||||
|
<key>^Resources/.*\.lproj/locversion.plist$</key>
|
||||||
|
<dict>
|
||||||
|
<key>omit</key>
|
||||||
|
<true/>
|
||||||
|
<key>weight</key>
|
||||||
|
<real>1100</real>
|
||||||
|
</dict>
|
||||||
|
<key>^Resources/Base\.lproj/</key>
|
||||||
|
<dict>
|
||||||
|
<key>weight</key>
|
||||||
|
<real>1010</real>
|
||||||
|
</dict>
|
||||||
|
<key>^[^/]+$</key>
|
||||||
|
<dict>
|
||||||
|
<key>nested</key>
|
||||||
|
<true/>
|
||||||
|
<key>weight</key>
|
||||||
|
<real>10</real>
|
||||||
|
</dict>
|
||||||
|
<key>^embedded\.provisionprofile$</key>
|
||||||
|
<dict>
|
||||||
|
<key>weight</key>
|
||||||
|
<real>20</real>
|
||||||
|
</dict>
|
||||||
|
<key>^version\.plist$</key>
|
||||||
|
<dict>
|
||||||
|
<key>weight</key>
|
||||||
|
<real>20</real>
|
||||||
|
</dict>
|
||||||
|
</dict>
|
||||||
|
</dict>
|
||||||
|
</plist>
|
229
Jumperless Wokwi Bridge App/JumperlessWokwiBridge.py
Normal file
229
Jumperless Wokwi Bridge App/JumperlessWokwiBridge.py
Normal file
@ -0,0 +1,229 @@
|
|||||||
|
from bs4 import BeautifulSoup
|
||||||
|
|
||||||
|
|
||||||
|
import requests
|
||||||
|
import json
|
||||||
|
import serial
|
||||||
|
import time
|
||||||
|
|
||||||
|
import serial.tools.list_ports
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
portSelected = 0
|
||||||
|
|
||||||
|
print("\n\r")
|
||||||
|
|
||||||
|
while portSelected == False:
|
||||||
|
|
||||||
|
ports = serial.tools.list_ports.comports()
|
||||||
|
i = 0
|
||||||
|
for port, desc, hwid in sorted(ports):
|
||||||
|
i = i + 1
|
||||||
|
print("{}: {} [{}]".format(i, port, desc))
|
||||||
|
|
||||||
|
selection = input ("\n\n\rSelect the port connected to your Jumperless ('r' to rescan)\n\n\r")
|
||||||
|
if selection.isdigit() == True and int(selection) <= i:
|
||||||
|
portName = ports[int(selection) - 1].device
|
||||||
|
portSelected = True
|
||||||
|
print(ports[int(selection) - 1].device)
|
||||||
|
#print(0 in ports)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#portName = '/dev/cu.usbmodem11301'
|
||||||
|
|
||||||
|
def portIsUsable(portName):
|
||||||
|
try:
|
||||||
|
ser = serial.Serial(port=portName)
|
||||||
|
return False
|
||||||
|
except:
|
||||||
|
return True
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
ser = serial.Serial(portName, 460800, timeout=0.050)
|
||||||
|
|
||||||
|
#the website URL
|
||||||
|
#url_link = "https://wokwi.com/projects/367384677537829889"
|
||||||
|
|
||||||
|
|
||||||
|
url_link = input('\n\n\rPaste the link to you Wokwi project here:\n\n\r')
|
||||||
|
|
||||||
|
print("\n\n\rSave your Wokwi project to update the Jumperless\n\n\r")
|
||||||
|
|
||||||
|
|
||||||
|
stringified = 0
|
||||||
|
lastDiagram = 1
|
||||||
|
|
||||||
|
while True:
|
||||||
|
result = requests.get(url_link).text
|
||||||
|
doc = BeautifulSoup(result, "html.parser")
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
s = doc.find('script', type='application/json').get_text()
|
||||||
|
|
||||||
|
stringex = str(s)
|
||||||
|
|
||||||
|
d = json.loads(stringex)
|
||||||
|
|
||||||
|
d = d['props']['pageProps']['p']['files'][1]['content']
|
||||||
|
|
||||||
|
f = json.loads(d)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
stringified = str(f)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
if lastDiagram != stringified:
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
length = len(f["connections"])
|
||||||
|
|
||||||
|
|
||||||
|
p = "{\n"
|
||||||
|
|
||||||
|
|
||||||
|
for i in range(length):
|
||||||
|
|
||||||
|
conn1 = str(f["connections"][i][0])
|
||||||
|
|
||||||
|
|
||||||
|
if conn1.startswith("bb1:") == True:
|
||||||
|
periodIndex = conn1.find('.')
|
||||||
|
conn1 = conn1[4:periodIndex]
|
||||||
|
|
||||||
|
if conn1.endswith('t') == True:
|
||||||
|
conn1 = conn1[0:(len(conn1)-1)]
|
||||||
|
elif conn1.endswith('b') == True:
|
||||||
|
conn1 = conn1[0:(len(conn1)-1)]
|
||||||
|
conn1 = int(conn1)
|
||||||
|
conn1 = conn1 + 30
|
||||||
|
conn1 = str(conn1)
|
||||||
|
elif conn1.endswith('n') == True:
|
||||||
|
conn1 = "100"
|
||||||
|
elif conn1.startswith("GND") == True:
|
||||||
|
conn1 = "100"
|
||||||
|
elif conn1.endswith('p') == True:
|
||||||
|
if conn1.startswith('t') == True:
|
||||||
|
conn1 = "105"
|
||||||
|
elif conn1.startswith('b') == True:
|
||||||
|
conn1 = "103"
|
||||||
|
|
||||||
|
|
||||||
|
if conn1.startswith("nano:") == True:
|
||||||
|
periodIndex = conn1.find('.')
|
||||||
|
conn1 = conn1[5:len(conn1)]
|
||||||
|
|
||||||
|
if conn1.startswith("GND") == True:
|
||||||
|
conn1 = "100"
|
||||||
|
elif conn1 == "AREF":
|
||||||
|
conn1 = "85"
|
||||||
|
elif conn1 == "RESET":
|
||||||
|
conn1 = "84"
|
||||||
|
elif conn1 == "5V":
|
||||||
|
conn1 = "105"
|
||||||
|
elif conn1 == "3.3V":
|
||||||
|
conn1 = "103"
|
||||||
|
elif conn1 == "5V":
|
||||||
|
conn1 = "105"
|
||||||
|
|
||||||
|
|
||||||
|
elif conn1.startswith("A") == True:
|
||||||
|
conn1 = conn1[1:(len(conn1))]
|
||||||
|
conn1 = int(conn1)
|
||||||
|
conn1 = conn1 + 86
|
||||||
|
conn1 = str(conn1)
|
||||||
|
elif conn1.isdigit() == True:
|
||||||
|
conn1 = int(conn1)
|
||||||
|
conn1 = conn1 + 70
|
||||||
|
conn1 = str(conn1)
|
||||||
|
|
||||||
|
|
||||||
|
conn2 = str(f["connections"][i][1])
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
if conn2.startswith("bb1:") == True:
|
||||||
|
periodIndex = conn2.find('.')
|
||||||
|
conn2 = conn2[4:periodIndex]
|
||||||
|
|
||||||
|
if conn2.endswith('t') == True:
|
||||||
|
conn2 = conn2[0:(len(conn2)-1)]
|
||||||
|
elif conn2.endswith('b') == True:
|
||||||
|
conn2 = conn2[0:(len(conn2)-1)]
|
||||||
|
conn2 = int(conn2)
|
||||||
|
conn2 = conn2 + 30
|
||||||
|
conn2 = str(conn2)
|
||||||
|
elif conn2.endswith('n') == True:
|
||||||
|
conn2 = "100"
|
||||||
|
elif conn2.startswith("GND") == True:
|
||||||
|
conn2 = "100"
|
||||||
|
elif conn2.endswith('p') == True:
|
||||||
|
if conn2.startswith('t') == True:
|
||||||
|
conn2 = "105"
|
||||||
|
elif conn2.startswith('b') == True:
|
||||||
|
conn2 = "103"
|
||||||
|
|
||||||
|
|
||||||
|
if conn2.startswith("nano:") == True:
|
||||||
|
periodIndex = conn2.find('.')
|
||||||
|
conn2 = conn2[5:len(conn2)]
|
||||||
|
|
||||||
|
if conn2.startswith("GND") == True:
|
||||||
|
conn2 = "100"
|
||||||
|
elif conn2 == "AREF":
|
||||||
|
conn2 = "85"
|
||||||
|
elif conn2 == "RESET":
|
||||||
|
conn2 = "84"
|
||||||
|
elif conn2 == "5V":
|
||||||
|
conn2 = "105"
|
||||||
|
elif conn2 == "3.3V":
|
||||||
|
conn2 = "103"
|
||||||
|
elif conn2 == "5V":
|
||||||
|
conn2 = "105"
|
||||||
|
|
||||||
|
elif conn2.startswith("A") == True and conn2 != "AREF":
|
||||||
|
|
||||||
|
conn2 = conn2[1:(len(conn2))]
|
||||||
|
conn2 = int(conn2)
|
||||||
|
conn2 = conn2 + 86
|
||||||
|
conn2 = str(conn2)
|
||||||
|
elif conn2.isdigit() == True:
|
||||||
|
conn2 = int(conn2)
|
||||||
|
conn2 = conn2 + 70
|
||||||
|
conn2 = str(conn2)
|
||||||
|
|
||||||
|
|
||||||
|
if conn1.isdigit()== True and conn2.isdigit() == True:
|
||||||
|
|
||||||
|
p = (p + conn1 + '-')
|
||||||
|
p = (p + conn2 + ',\n')
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
p = (p + "}\n{\n}")
|
||||||
|
|
||||||
|
lastDiagram = stringified
|
||||||
|
|
||||||
|
|
||||||
|
ser.write('f'.encode())
|
||||||
|
|
||||||
|
time.sleep(0.1)
|
||||||
|
|
||||||
|
ser.write(p.encode())
|
||||||
|
|
||||||
|
#print (p)
|
||||||
|
|
||||||
|
else:
|
||||||
|
time.sleep(0.5)
|
||||||
|
|
||||||
|
|
1
JumperlessNano/data/lastCommand.txt
Normal file
1
JumperlessNano/data/lastCommand.txt
Normal file
@ -0,0 +1 @@
|
|||||||
|
f
|
@ -1,14 +1,17 @@
|
|||||||
bridges
|
bridges
|
||||||
{
|
{
|
||||||
10-33,
|
45-100,
|
||||||
23-57,
|
15-105,
|
||||||
20-SUPPLY_3V3,
|
23-16,
|
||||||
58-GND,
|
29-105,
|
||||||
57-DAC0_5V,
|
53-16,
|
||||||
47-I_P,
|
17-46,
|
||||||
45-I_N,
|
17-4,
|
||||||
DAC1_8V-36,
|
5-100,
|
||||||
ADC3_8V-2,
|
36-33,
|
||||||
ADC0_5V-DAC0_5V,
|
32-100,
|
||||||
|
42-47,
|
||||||
|
48-105,
|
||||||
|
58-46,
|
||||||
}
|
}
|
||||||
|
|
@ -5,52 +5,27 @@
|
|||||||
"parts": [
|
"parts": [
|
||||||
{ "type": "wokwi-breadboard-half", "id": "bb1", "top": -694.2, "left": -141.2, "attrs": {} },
|
{ "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-arduino-nano", "id": "nano", "top": -791, "left": -62.59, "attrs": {} },
|
||||||
{
|
{ "type": "wokwi-led", "id": "led1", "top": -666, "left": -92.2, "attrs": { "color": "red" } },
|
||||||
"type": "wokwi-led",
|
|
||||||
"id": "led1",
|
|
||||||
"top": -675.6,
|
|
||||||
"left": -82.6,
|
|
||||||
"attrs": { "color": "red" }
|
|
||||||
},
|
|
||||||
{
|
{
|
||||||
"type": "wokwi-resistor",
|
"type": "wokwi-resistor",
|
||||||
"id": "r1",
|
"id": "r1",
|
||||||
"top": -600.85,
|
"top": -629.65,
|
||||||
"left": -57.6,
|
"left": 19.2,
|
||||||
"attrs": { "value": "1000" }
|
"attrs": { "value": "1000" }
|
||||||
},
|
},
|
||||||
{ "type": "wokwi-gnd", "id": "gnd1", "top": -1036.8, "left": -77.4, "attrs": {} },
|
{ "type": "wokwi-gnd", "id": "gnd1", "top": -671.42, "left": 210.03, "attrs": {} },
|
||||||
{ "type": "wokwi-vcc", "id": "vcc1", "top": -901.13, "left": 98.33, "attrs": {} }
|
{ "type": "wokwi-vcc", "id": "vcc1", "top": -757.34, "left": 201.2, "attrs": {} }
|
||||||
],
|
],
|
||||||
"connections": [
|
"connections": [
|
||||||
[ "bb1:15b.j", "nano:12", "gold", [ "v0" ] ],
|
[ "vcc1:VCC", "bb1:tp.25", "red", [ "v18.96", "h-49.2" ] ],
|
||||||
[ "bb1:19b.j", "nano:9", "green", [ "h93.92", "v-248.6" ] ],
|
[ "led1:A", "bb1:6t.c", "", [ "$bb" ] ],
|
||||||
[ "nano:A2", "bb1:tn.8", "orange", [ "v0" ] ],
|
[ "led1:C", "bb1:5t.c", "", [ "$bb" ] ],
|
||||||
[ "r1:2", "bb1:13t.a", "green", [ "v0" ] ],
|
[ "r1:1", "bb1:15t.c", "", [ "$bb" ] ],
|
||||||
[ "bb1:17t.d", "nano:A5", "purple", [ "v0" ] ],
|
[ "r1:2", "bb1:21t.c", "", [ "$bb" ] ],
|
||||||
[ "r1:1", "bb1:7t.c", "green", [ "v0" ] ],
|
[ "bb1:15t.e", "bb1:6t.e", "black", [ "v11.61", "h-84.29" ] ],
|
||||||
[ "bb1:9b.g", "bb1:9b.i", "green", [ "v0" ] ],
|
[ "bb1:21t.a", "bb1:tn.18", "black", [ "v0" ] ],
|
||||||
[ "bb1:20t.c", "bb1:23t.c", "green", [ "v0" ] ],
|
[ "bb1:5t.d", "bb1:tp.2", "red", [ "h-18.93", "v-67.5" ] ],
|
||||||
[ "bb1:5b.j", "bb1:11b.j", "green", [ "v0" ] ],
|
[ "gnd1:GND", "bb1:tn.25", "black", [ "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": {}
|
"dependencies": {}
|
||||||
}
|
}
|
@ -13,9 +13,10 @@ 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
|
upload_port = /dev/cu.usbmodem11301
|
||||||
monitor_port = /dev/cu.usbmodem1301
|
monitor_port = /dev/cu.usbmodem11301
|
||||||
extra_scripts = post:scripts/extra_script.py
|
extra_scripts = post:scripts/extra_script.py
|
||||||
|
monitor_speed = 256000
|
||||||
|
|
||||||
[env:pico]
|
[env:pico]
|
||||||
board = pico
|
board = pico
|
||||||
|
@ -248,7 +248,7 @@ void sendPath(int i, int setOrClear)
|
|||||||
|
|
||||||
// delayMicroseconds(50);
|
// delayMicroseconds(50);
|
||||||
|
|
||||||
delayMicroseconds(30);
|
delayMicroseconds(20);
|
||||||
|
|
||||||
pio_sm_put(pio, sm, chAddress);
|
pio_sm_put(pio, sm, chAddress);
|
||||||
|
|
||||||
|
@ -7,19 +7,21 @@
|
|||||||
#include "NetManager.h"
|
#include "NetManager.h"
|
||||||
#include "JumperlessDefinesRP2040.h"
|
#include "JumperlessDefinesRP2040.h"
|
||||||
#include "LEDs.h"
|
#include "LEDs.h"
|
||||||
|
#include <EEPROM.h>
|
||||||
|
|
||||||
|
|
||||||
static bool debugFP;
|
|
||||||
static bool debugFPtime;
|
bool debugFP = EEPROM.read(DEBUG_FILEPARSINGADDRESS);
|
||||||
|
bool debugFPtime = EEPROM.read(TIME_FILEPARSINGADDRESS);
|
||||||
|
|
||||||
createSafeString(nodeFileString, 1200);
|
createSafeString(nodeFileString, 1200);
|
||||||
|
|
||||||
createSafeString(nodeString, 1200);
|
createSafeString(nodeString, 1200);
|
||||||
createSafeString(specialFunctionsString, 800);
|
createSafeString(specialFunctionsString, 800);
|
||||||
|
|
||||||
char inputBuffer[5000] = {0};
|
char inputBuffer[8000] = {0};
|
||||||
|
|
||||||
ArduinoJson::StaticJsonDocument<5000> wokwiJson;
|
ArduinoJson::StaticJsonDocument<8000> wokwiJson;
|
||||||
|
|
||||||
String connectionsW[MAX_BRIDGES][5];
|
String connectionsW[MAX_BRIDGES][5];
|
||||||
|
|
||||||
@ -30,20 +32,35 @@ unsigned long timeToFP = 0;
|
|||||||
|
|
||||||
int numConnsJson = 0;
|
int numConnsJson = 0;
|
||||||
|
|
||||||
|
void savePreformattedNodeFile (void)
|
||||||
|
{
|
||||||
|
LittleFS.remove("nodeFile.txt");
|
||||||
|
|
||||||
|
nodeFile = LittleFS.open("nodeFile.txt", "w+");
|
||||||
|
|
||||||
|
while (Serial.available() == 0)
|
||||||
|
{
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
while (Serial.available() > 0)
|
||||||
|
{
|
||||||
|
nodeFile.write(Serial.read());
|
||||||
|
delay(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
nodeFile.close();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
void parseWokwiFileToNodeFile(void)
|
void parseWokwiFileToNodeFile(void)
|
||||||
{
|
{
|
||||||
|
|
||||||
delay(3000);
|
// delay(3000);
|
||||||
LittleFS.begin();
|
LittleFS.begin();
|
||||||
timeToFP = millis();
|
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+");
|
wokwiFile = LittleFS.open("wokwi.txt", "w+");
|
||||||
if (!wokwiFile)
|
if (!wokwiFile)
|
||||||
@ -55,248 +72,279 @@ void parseWokwiFileToNodeFile(void)
|
|||||||
else
|
else
|
||||||
{
|
{
|
||||||
if (debugFP)
|
if (debugFP)
|
||||||
Serial.println("\n\ropened wokwi.txt\n\n\n\r");
|
{
|
||||||
|
Serial.println("\n\ropened wokwi.txt\n\r");
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
// Serial.println("\n\r");
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
Serial.println("paste Wokwi diagram.json here");
|
Serial.println("paste Wokwi diagram.json here\n\r");
|
||||||
while (Serial.available() == 0)
|
while (Serial.available() == 0)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
int numCharsRead = 0;
|
int numCharsRead = 0;
|
||||||
|
|
||||||
|
char firstChar = Serial.read();
|
||||||
|
|
||||||
|
if (firstChar != '{') // in case you just paste a wokwi file in from the menu, the opening brace will have already been read
|
||||||
|
{
|
||||||
|
inputBuffer[numCharsRead] = '{';
|
||||||
|
numCharsRead++;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
inputBuffer[numCharsRead] = firstChar;
|
||||||
|
numCharsRead++;
|
||||||
|
}
|
||||||
|
/*
|
||||||
|
Serial.println(firstChar);
|
||||||
|
Serial.println(firstChar);
|
||||||
|
Serial.println(firstChar);
|
||||||
|
Serial.println(firstChar);
|
||||||
|
Serial.println(firstChar);
|
||||||
|
Serial.print(firstChar);
|
||||||
|
*/
|
||||||
|
delay(1);
|
||||||
while (Serial.available() > 0)
|
while (Serial.available() > 0)
|
||||||
{
|
{
|
||||||
char c = Serial.read();
|
char c = Serial.read();
|
||||||
inputBuffer[numCharsRead] = c;
|
inputBuffer[numCharsRead] = c;
|
||||||
|
|
||||||
numCharsRead++;
|
numCharsRead++;
|
||||||
delay(1);
|
|
||||||
|
delayMicroseconds(1000);
|
||||||
}
|
}
|
||||||
|
|
||||||
createSafeStringFromCharArray(wokwiFileString, inputBuffer);
|
createSafeStringFromCharArray(wokwiFileString, inputBuffer);
|
||||||
delay(10);
|
delay(10);
|
||||||
wokwiFile.write(inputBuffer, numCharsRead);
|
wokwiFile.write(inputBuffer, numCharsRead);
|
||||||
|
|
||||||
delay(10);
|
delay(10);
|
||||||
|
|
||||||
wokwiFile.seek(0);
|
wokwiFile.seek(0);
|
||||||
|
|
||||||
|
if (debugFP)
|
||||||
Serial.println("\n\n\rwokwiFile\n\n\r");
|
Serial.println("\n\n\rwokwiFile\n\n\r");
|
||||||
|
|
||||||
/* for (int i = 0; i < numCharsRead; i++)
|
/* for (int i = 0; i < numCharsRead; i++)
|
||||||
|
{
|
||||||
|
Serial.print((char)wokwiFile.read());
|
||||||
|
}*/
|
||||||
|
if (debugFP)
|
||||||
{
|
{
|
||||||
Serial.print((char)wokwiFile.read());
|
Serial.print(wokwiFileString);
|
||||||
}*/
|
|
||||||
|
|
||||||
Serial.print(wokwiFileString);
|
Serial.println("\n\n\rnumCharsRead = ");
|
||||||
|
|
||||||
Serial.println("\n\n\rnumCharsRead\n\n\r");
|
Serial.print(numCharsRead);
|
||||||
|
|
||||||
Serial.print(numCharsRead);
|
|
||||||
|
|
||||||
|
Serial.println("\n\n\r");
|
||||||
|
}
|
||||||
wokwiFile.close();
|
wokwiFile.close();
|
||||||
|
|
||||||
deserializeJson(wokwiJson, inputBuffer);
|
deserializeJson(wokwiJson, inputBuffer);
|
||||||
|
|
||||||
Serial.println("\n\n\rwokwiJson\n\n\r");
|
if (debugFP)
|
||||||
|
|
||||||
//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.println("\n\n\rwokwiJson\n\n\r");
|
||||||
|
|
||||||
|
Serial.println("\n\n\rconnectionsW\n\n\r");
|
||||||
}
|
}
|
||||||
Serial.print(connectionsW[i][0]);
|
|
||||||
Serial.print(", \t ");
|
|
||||||
|
|
||||||
Serial.print(connectionsW[i][1]);
|
numConnsJson = wokwiJson["connections"].size();
|
||||||
Serial.print(", \t ");
|
|
||||||
|
|
||||||
Serial.print(connectionsW[i][2]);
|
copyArray(wokwiJson["connections"], connectionsW);
|
||||||
Serial.print(", \t ");
|
|
||||||
|
|
||||||
Serial.print(connectionsW[i][3]);
|
// deserializeJson(connectionsW, Serial);
|
||||||
Serial.print(", \t ");
|
if (debugFP)
|
||||||
|
{
|
||||||
|
Serial.println(wokwiJson["connections"].size());
|
||||||
|
|
||||||
Serial.print(connectionsW[i][4]);
|
for (int i = 0; i < MAX_BRIDGES; i++)
|
||||||
Serial.print(", \t ");
|
{
|
||||||
|
// Serial.println(wokwiJson["connections"].size());
|
||||||
|
if (connectionsW[i][0] == "")
|
||||||
|
{
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
Serial.print(connectionsW[i][0]);
|
||||||
|
Serial.print(", \t ");
|
||||||
|
|
||||||
Serial.println();
|
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);
|
||||||
|
openNodeFile();
|
||||||
}
|
}
|
||||||
|
|
||||||
Serial.println("\n\n\rRedefining\n\n\r");
|
|
||||||
|
|
||||||
|
|
||||||
changeWokwiDefinesToJumperless();
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
writeToNodeFile();
|
|
||||||
//while(1);
|
|
||||||
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void changeWokwiDefinesToJumperless(void)
|
void changeWokwiDefinesToJumperless(void)
|
||||||
{
|
{
|
||||||
|
|
||||||
String connString1 = " ";
|
String connString1 = " ";
|
||||||
String connString2 = " ";
|
String connString2 = " ";
|
||||||
String connStringColor = " ";
|
String connStringColor = " ";
|
||||||
String bb = "bb1:";
|
String bb = "bb1:";
|
||||||
|
|
||||||
|
int nodeNumber;
|
||||||
|
|
||||||
int nodeNumber;
|
for (int i = 0; i < numConnsJson; i++)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
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;
|
if (debugFP)
|
||||||
//Serial.println("bottom");
|
{
|
||||||
connString1.substring(0,connString1.length()-1);
|
Serial.println(' ');
|
||||||
nodeNumber += connString1.toInt();
|
}
|
||||||
|
for (int j = 0; j < 2; j++)
|
||||||
|
{
|
||||||
|
nodeNumber = -1;
|
||||||
|
connString1 = connectionsW[i][j];
|
||||||
|
if (debugFP)
|
||||||
|
{
|
||||||
|
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 if (connString1.startsWith("pot1:"))
|
||||||
|
{
|
||||||
|
nodeNumber = DAC0_5V;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
|
||||||
|
connectionsW[i][j] = -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
// nodeNumber += connString1.toInt();
|
||||||
|
|
||||||
|
connectionsW[i][j] = nodeNumber;
|
||||||
|
if (debugFP)
|
||||||
|
{
|
||||||
|
Serial.print(connectionsW[i][j]);
|
||||||
|
|
||||||
|
Serial.print(" \t ");
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
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 clearNodeFile(void)
|
||||||
|
{
|
||||||
|
LittleFS.remove("nodeFile.txt");
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -317,7 +365,7 @@ void writeToNodeFile(void)
|
|||||||
if (debugFP)
|
if (debugFP)
|
||||||
Serial.println("\n\rrecreated nodeFile.txt\n\n\rloading bridges from wokwi.txt\n\r");
|
Serial.println("\n\rrecreated nodeFile.txt\n\n\rloading bridges from wokwi.txt\n\r");
|
||||||
}
|
}
|
||||||
nodeFile.print("{\n\r");
|
nodeFile.print("{\n\r");
|
||||||
for (int i = 0; i < numConnsJson; i++)
|
for (int i = 0; i < numConnsJson; i++)
|
||||||
{
|
{
|
||||||
if (connectionsW[i][0] == "-1" && connectionsW[i][1] != "-1")
|
if (connectionsW[i][0] == "-1" && connectionsW[i][1] != "-1")
|
||||||
@ -330,7 +378,7 @@ nodeFile.print("{\n\r");
|
|||||||
lightUpNode(connectionsW[i][1].toInt());
|
lightUpNode(connectionsW[i][1].toInt());
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
if (connectionsW[i][0] == connectionsW[i][1])
|
if (connectionsW[i][0] == connectionsW[i][1])
|
||||||
{
|
{
|
||||||
lightUpNode(connectionsW[i][0].toInt());
|
lightUpNode(connectionsW[i][0].toInt());
|
||||||
continue;
|
continue;
|
||||||
@ -340,40 +388,30 @@ nodeFile.print("{\n\r");
|
|||||||
nodeFile.print("-");
|
nodeFile.print("-");
|
||||||
nodeFile.print(connectionsW[i][1]);
|
nodeFile.print(connectionsW[i][1]);
|
||||||
nodeFile.print(",\n\r");
|
nodeFile.print(",\n\r");
|
||||||
|
|
||||||
}
|
}
|
||||||
nodeFile.print("}\n\r");
|
nodeFile.print("}\n\r");
|
||||||
|
|
||||||
Serial.println("wrote to nodeFile.txt");
|
if (debugFP)
|
||||||
|
{
|
||||||
Serial.println("nodeFile.txt contents:");
|
Serial.println("wrote to nodeFile.txt");
|
||||||
nodeFile.seek(0);
|
|
||||||
while (nodeFile.available())
|
|
||||||
{
|
|
||||||
Serial.write(nodeFile.read());
|
|
||||||
}
|
|
||||||
Serial.println("\n\r");
|
|
||||||
|
|
||||||
|
Serial.println("nodeFile.txt contents:");
|
||||||
|
nodeFile.seek(0);
|
||||||
|
|
||||||
|
while (nodeFile.available())
|
||||||
|
{
|
||||||
|
Serial.write(nodeFile.read());
|
||||||
|
}
|
||||||
|
Serial.println("\n\r");
|
||||||
|
}
|
||||||
nodeFile.close();
|
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
|
|
||||||
else
|
|
||||||
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)
|
||||||
@ -437,6 +475,7 @@ void replaceSFNamesWithDefinedInts(void)
|
|||||||
{
|
{
|
||||||
if (debugFP)
|
if (debugFP)
|
||||||
Serial.println("replacing special function names with defined ints\n\r");
|
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");
|
||||||
@ -460,6 +499,7 @@ void replaceNanoNamesWithDefinedInts(void) // for dome reason Arduino's String w
|
|||||||
{
|
{
|
||||||
if (debugFP)
|
if (debugFP)
|
||||||
Serial.println("replacing special function names with defined ints\n\r");
|
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);
|
||||||
@ -616,7 +656,7 @@ void parseStringToBridges(void)
|
|||||||
|
|
||||||
// if(debugFP)Serial.println(nodeFileString);
|
// if(debugFP)Serial.println(nodeFileString);
|
||||||
timeToFP = millis() - timeToFP;
|
timeToFP = millis() - timeToFP;
|
||||||
if (debugFP)
|
if (debugFPtime)
|
||||||
Serial.print("\n\rtook ");
|
Serial.print("\n\rtook ");
|
||||||
|
|
||||||
if (debugFPtime)
|
if (debugFPtime)
|
||||||
@ -624,3 +664,232 @@ void parseStringToBridges(void)
|
|||||||
if (debugFPtime)
|
if (debugFPtime)
|
||||||
Serial.println("ms to open and parse file\n\r");
|
Serial.println("ms to open and parse file\n\r");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void debugFlagInit(void)
|
||||||
|
{
|
||||||
|
debugFP = EEPROM.read(DEBUG_FILEPARSINGADDRESS);
|
||||||
|
debugFPtime = EEPROM.read(TIME_FILEPARSINGADDRESS);
|
||||||
|
|
||||||
|
debugNM = EEPROM.read(DEBUG_NETMANAGERADDRESS);
|
||||||
|
debugNMtime = EEPROM.read(TIME_NETMANAGERADDRESS);
|
||||||
|
|
||||||
|
debugNTCC = EEPROM.read(DEBUG_NETTOCHIPCONNECTIONSADDRESS);
|
||||||
|
debugNTCC2 = EEPROM.read(DEBUG_NETTOCHIPCONNECTIONSALTADDRESS);
|
||||||
|
|
||||||
|
debugLEDs = EEPROM.read(DEBUG_LEDSADDRESS);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void debugFlagSet(int flag)
|
||||||
|
{
|
||||||
|
int flagStatus;
|
||||||
|
switch (flag)
|
||||||
|
{
|
||||||
|
case 1:
|
||||||
|
{
|
||||||
|
flagStatus = EEPROM.read(DEBUG_FILEPARSINGADDRESS);
|
||||||
|
if (flagStatus == 1)
|
||||||
|
{
|
||||||
|
EEPROM.write(DEBUG_FILEPARSINGADDRESS, 0);
|
||||||
|
|
||||||
|
debugFP = false;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
EEPROM.write(DEBUG_FILEPARSINGADDRESS, 1);
|
||||||
|
|
||||||
|
debugFP = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 2:
|
||||||
|
{
|
||||||
|
flagStatus = EEPROM.read(TIME_FILEPARSINGADDRESS);
|
||||||
|
|
||||||
|
if (flagStatus == 1)
|
||||||
|
{
|
||||||
|
EEPROM.write(TIME_FILEPARSINGADDRESS, 0);
|
||||||
|
|
||||||
|
debugFPtime = false;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
EEPROM.write(TIME_FILEPARSINGADDRESS, 1);
|
||||||
|
|
||||||
|
debugFPtime = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 3:
|
||||||
|
{
|
||||||
|
flagStatus = EEPROM.read(DEBUG_NETMANAGERADDRESS);
|
||||||
|
|
||||||
|
if (flagStatus == 1)
|
||||||
|
{
|
||||||
|
EEPROM.write(DEBUG_NETMANAGERADDRESS, 0);
|
||||||
|
|
||||||
|
debugNM = false;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
EEPROM.write(DEBUG_NETMANAGERADDRESS, 1);
|
||||||
|
|
||||||
|
debugNM = true;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 4:
|
||||||
|
{
|
||||||
|
flagStatus = EEPROM.read(TIME_NETMANAGERADDRESS);
|
||||||
|
|
||||||
|
if (flagStatus == 1)
|
||||||
|
{
|
||||||
|
EEPROM.write(TIME_NETMANAGERADDRESS, 0);
|
||||||
|
|
||||||
|
debugNMtime = false;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
EEPROM.write(TIME_NETMANAGERADDRESS, 1);
|
||||||
|
|
||||||
|
debugNMtime = true;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 5:
|
||||||
|
{
|
||||||
|
flagStatus = EEPROM.read(DEBUG_NETTOCHIPCONNECTIONSADDRESS);
|
||||||
|
|
||||||
|
if (flagStatus == 1)
|
||||||
|
{
|
||||||
|
EEPROM.write(DEBUG_NETTOCHIPCONNECTIONSADDRESS, 0);
|
||||||
|
|
||||||
|
debugNTCC = false;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
EEPROM.write(DEBUG_NETTOCHIPCONNECTIONSADDRESS, 1);
|
||||||
|
|
||||||
|
debugNTCC = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 6:
|
||||||
|
{
|
||||||
|
flagStatus = EEPROM.read(DEBUG_NETTOCHIPCONNECTIONSALTADDRESS);
|
||||||
|
if (flagStatus == 1)
|
||||||
|
{
|
||||||
|
EEPROM.write(DEBUG_NETTOCHIPCONNECTIONSALTADDRESS, 0);
|
||||||
|
|
||||||
|
debugNTCC2 = false;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
EEPROM.write(DEBUG_NETTOCHIPCONNECTIONSALTADDRESS, 1);
|
||||||
|
|
||||||
|
debugNTCC2 = true;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
case 7:
|
||||||
|
{
|
||||||
|
flagStatus = EEPROM.read(DEBUG_LEDSADDRESS);
|
||||||
|
|
||||||
|
if (flagStatus == 1)
|
||||||
|
{
|
||||||
|
EEPROM.write(DEBUG_LEDSADDRESS, 0);
|
||||||
|
|
||||||
|
debugLEDs = false;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
EEPROM.write(DEBUG_LEDSADDRESS, 1);
|
||||||
|
|
||||||
|
debugLEDs = true;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
case 0:
|
||||||
|
{
|
||||||
|
EEPROM.write(DEBUG_FILEPARSINGADDRESS, 0);
|
||||||
|
EEPROM.write(TIME_FILEPARSINGADDRESS, 0);
|
||||||
|
EEPROM.write(DEBUG_NETMANAGERADDRESS, 0);
|
||||||
|
EEPROM.write(TIME_NETMANAGERADDRESS, 0);
|
||||||
|
EEPROM.write(DEBUG_NETTOCHIPCONNECTIONSADDRESS, 0);
|
||||||
|
EEPROM.write(DEBUG_NETTOCHIPCONNECTIONSALTADDRESS, 0);
|
||||||
|
EEPROM.write(DEBUG_LEDSADDRESS, 0);
|
||||||
|
debugFP = false;
|
||||||
|
debugFPtime = false;
|
||||||
|
debugNM = false;
|
||||||
|
debugNMtime = false;
|
||||||
|
debugNTCC = false;
|
||||||
|
debugNTCC2 = false;
|
||||||
|
debugLEDs = false;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
case 9:
|
||||||
|
{
|
||||||
|
EEPROM.write(DEBUG_FILEPARSINGADDRESS, 1);
|
||||||
|
EEPROM.write(TIME_FILEPARSINGADDRESS, 1);
|
||||||
|
EEPROM.write(DEBUG_NETMANAGERADDRESS, 1);
|
||||||
|
EEPROM.write(TIME_NETMANAGERADDRESS, 1);
|
||||||
|
EEPROM.write(DEBUG_NETTOCHIPCONNECTIONSADDRESS, 1);
|
||||||
|
EEPROM.write(DEBUG_NETTOCHIPCONNECTIONSALTADDRESS, 1);
|
||||||
|
EEPROM.write(DEBUG_LEDSADDRESS, 1);
|
||||||
|
debugFP = true;
|
||||||
|
debugFPtime = true;
|
||||||
|
debugNM = true;
|
||||||
|
debugNMtime = true;
|
||||||
|
debugNTCC = true;
|
||||||
|
debugNTCC2 = true;
|
||||||
|
debugLEDs = true;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
EEPROM.commit();
|
||||||
|
}
|
||||||
|
|
||||||
|
void runCommandAfterReset(char command)
|
||||||
|
{
|
||||||
|
if (EEPROM.read(CLEARBEFORECOMMANDADDRESS) == 1)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
|
||||||
|
EEPROM.write(CLEARBEFORECOMMANDADDRESS, 1);
|
||||||
|
EEPROM.write(LASTCOMMANDADDRESS, command);
|
||||||
|
EEPROM.commit();
|
||||||
|
|
||||||
|
digitalWrite(RESETPIN, HIGH);
|
||||||
|
delay(1);
|
||||||
|
digitalWrite(RESETPIN, LOW);
|
||||||
|
|
||||||
|
AIRCR_Register = 0x5FA0004; // hard reset
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
char lastCommandRead(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
Serial.print("last command: ");
|
||||||
|
|
||||||
|
Serial.println((char)EEPROM.read(LASTCOMMANDADDRESS));
|
||||||
|
|
||||||
|
return EEPROM.read(LASTCOMMANDADDRESS);
|
||||||
|
}
|
||||||
|
void lastCommandWrite(char lastCommand)
|
||||||
|
{
|
||||||
|
|
||||||
|
EEPROM.write(LASTCOMMANDADDRESS, lastCommand);
|
||||||
|
}
|
@ -1,12 +1,26 @@
|
|||||||
#ifndef FILEPARSING_H
|
#ifndef FILEPARSING_H
|
||||||
#define FILEPARSING_H
|
#define FILEPARSING_H
|
||||||
|
|
||||||
|
extern bool debugFP;
|
||||||
|
extern bool debugFPtime;
|
||||||
|
|
||||||
|
extern bool debugNM;
|
||||||
|
extern bool debugNMtime;
|
||||||
|
|
||||||
|
extern bool debugNTCC;
|
||||||
|
extern bool debugNTCC2;
|
||||||
|
|
||||||
|
extern bool debugLEDs;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//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 parseWokwiFileToNodeFile();
|
||||||
void changeWokwiDefinesToJumperless ();
|
void changeWokwiDefinesToJumperless ();
|
||||||
void writeToNodeFile(void);
|
void writeToNodeFile(void);
|
||||||
|
|
||||||
|
void savePreformattedNodeFile (void);
|
||||||
|
|
||||||
void openNodeFile();
|
void openNodeFile();
|
||||||
|
|
||||||
void splitStringToFields();
|
void splitStringToFields();
|
||||||
@ -17,6 +31,13 @@ void replaceNanoNamesWithDefinedInts();
|
|||||||
|
|
||||||
void parseStringToBridges();
|
void parseStringToBridges();
|
||||||
|
|
||||||
|
char lastCommandRead(void);
|
||||||
|
void lastCommandWrite(char lastCommand);
|
||||||
|
|
||||||
|
void runCommandAfterReset(char);
|
||||||
|
|
||||||
|
void debugFlagSet(int flag);
|
||||||
|
void debugFlagInit(void);
|
||||||
|
void clearNodeFile(void);
|
||||||
|
|
||||||
#endif
|
#endif
|
@ -1,15 +1,26 @@
|
|||||||
|
|
||||||
|
|
||||||
#define DEBUG_FILEPARSING 1
|
#define DEBUG_FILEPARSINGADDRESS 32
|
||||||
#define TIME_FILEPARSING 1
|
#define TIME_FILEPARSINGADDRESS 33
|
||||||
#define DEBUG_NETMANAGER 0
|
#define DEBUG_NETMANAGERADDRESS 34
|
||||||
#define TIME_NETMANAGER 1
|
#define TIME_NETMANAGERADDRESS 35
|
||||||
|
#define DEBUG_LEDSADDRESS 36
|
||||||
|
#define DEBUG_NETTOCHIPCONNECTIONSADDRESS 37
|
||||||
|
#define DEBUG_NETTOCHIPCONNECTIONSALTADDRESS 38
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#define MAX_NETS 64
|
#define MAX_NETS 64
|
||||||
#define MAX_BRIDGES 255
|
#define MAX_BRIDGES 255
|
||||||
#define MAX_NODES 64
|
#define MAX_NODES 64
|
||||||
#define MAX_DNI 8 //max number of doNotIntersect rules
|
#define MAX_DNI 8 //max number of doNotIntersect rules
|
||||||
|
|
||||||
|
#define LASTCOMMANDADDRESS 1
|
||||||
|
#define CLEARBEFORECOMMANDADDRESS 4
|
||||||
|
|
||||||
|
#define AIRCR_Register (*((volatile uint32_t *)(PPB_BASE + 0x0ED0C)))
|
||||||
|
|
||||||
|
|
||||||
#define CHIP_A 0
|
#define CHIP_A 0
|
||||||
|
@ -2,13 +2,33 @@
|
|||||||
#include <Adafruit_NeoPixel.h>
|
#include <Adafruit_NeoPixel.h>
|
||||||
#include "NetsToChipConnections.h"
|
#include "NetsToChipConnections.h"
|
||||||
#include "MatrixStateRP2040.h"
|
#include "MatrixStateRP2040.h"
|
||||||
|
#include <EEPROM.h>
|
||||||
|
|
||||||
Adafruit_NeoPixel leds(LED_COUNT, LED_PIN, NEO_GRB + NEO_KHZ800);
|
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 = 254;
|
uint8_t brightness = BRIGHTNESS;
|
||||||
|
|
||||||
|
bool debugLEDs = EEPROM.read(DEBUG_LEDSADDRESS);
|
||||||
|
|
||||||
|
rgbColor specialNetColors[8] =
|
||||||
|
{{00, 00, 00},
|
||||||
|
{0x00, 0xFF, 0x30},
|
||||||
|
{0xFF, 0x41, 0x14},
|
||||||
|
{0xFF, 0x10, 0x40},
|
||||||
|
{0xFF, 0x78, 0xaa},
|
||||||
|
{0xFF, 0x40, 0x78},
|
||||||
|
{0xFF, 0xff, 0xff},
|
||||||
|
{0xff, 0xFF, 0xff}};
|
||||||
|
|
||||||
|
rgbColor railColors[4] =
|
||||||
|
{
|
||||||
|
{0xFF, 0x41, 0x14},
|
||||||
|
{0x00, 0xFF, 0x30},
|
||||||
|
{0xFF, 0x00, 0x40},
|
||||||
|
{0x00, 0xFF, 0x30}};
|
||||||
|
|
||||||
void initLEDs(void)
|
void initLEDs(void)
|
||||||
{
|
{
|
||||||
@ -18,6 +38,8 @@ void initLEDs(void)
|
|||||||
leds.setBrightness(BRIGHTNESS);
|
leds.setBrightness(BRIGHTNESS);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void colorWipe(uint32_t color, int wait)
|
void colorWipe(uint32_t color, int wait)
|
||||||
{
|
{
|
||||||
|
|
||||||
@ -48,11 +70,22 @@ void rainbowy(int saturation, int brightness, int wait)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void clearLEDs(void)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < 59; i++)
|
||||||
|
{ // For each pixel in strip...
|
||||||
|
|
||||||
|
leds.setPixelColor(i, 0); // Set pixel's color (in RAM)
|
||||||
|
// Update strip to match
|
||||||
|
}
|
||||||
|
leds.show();
|
||||||
|
}
|
||||||
|
|
||||||
void assignNetColors(void)
|
void assignNetColors(void)
|
||||||
{
|
{
|
||||||
// numberOfNets = 60;
|
// numberOfNets = 60;
|
||||||
|
|
||||||
uint16_t colorDistance = 255 / numberOfNets;
|
uint16_t colorDistance = (255 / (numberOfNets-2));
|
||||||
|
|
||||||
/* rgbColor specialNetColors[8] =
|
/* rgbColor specialNetColors[8] =
|
||||||
{0x000000,
|
{0x000000,
|
||||||
@ -64,36 +97,25 @@ void assignNetColors(void)
|
|||||||
0xFFC8C8,
|
0xFFC8C8,
|
||||||
0xC8FFC8};
|
0xC8FFC8};
|
||||||
*/
|
*/
|
||||||
rgbColor specialNetColors[8] =
|
|
||||||
{{00, 00, 00},
|
|
||||||
{0x00, 0xFF, 0x30},
|
|
||||||
{0xFF, 0x41, 0x14},
|
|
||||||
{0xFF, 0x10, 0x40},
|
|
||||||
{0xFF, 0x78, 0x00},
|
|
||||||
{0xFF, 0x40, 0x78},
|
|
||||||
{0xFF, 0xC8, 0xC8},
|
|
||||||
{0xC8, 0xFF, 0xC8}};
|
|
||||||
|
|
||||||
rgbColor railColors[4] =
|
if (debugLEDs)
|
||||||
{
|
{
|
||||||
{0xFF, 0x41, 0x14},
|
Serial.print("\n\rcolorDistance: ");
|
||||||
{0x00, 0xFF, 0x30},
|
|
||||||
{0xFF, 0x00, 0x40},
|
|
||||||
{0x00, 0xFF, 0x30}};
|
|
||||||
|
|
||||||
Serial.print("colorDistance: ");
|
|
||||||
Serial.print(colorDistance);
|
Serial.print(colorDistance);
|
||||||
Serial.print("\n\r");
|
Serial.print("\n\r");
|
||||||
Serial.print("numberOfNets: ");
|
Serial.print("numberOfNets: ");
|
||||||
Serial.print(numberOfNets);
|
Serial.print(numberOfNets);
|
||||||
Serial.print("\n\rassigning net colors\n\r");
|
Serial.print("\n\rassigning net colors\n\r");
|
||||||
|
Serial.print("\n\rNet\t\tR\tG\tB\t\tH\tS\tV");
|
||||||
|
}
|
||||||
for (int i = 0; i < 8; i++)
|
for (int i = 0; i < 8; i++)
|
||||||
{
|
{
|
||||||
hsvColor netHsv = RgbToHsv(specialNetColors[i]);
|
hsvColor netHsv = RgbToHsv(specialNetColors[i]);
|
||||||
|
|
||||||
netColors[i] = specialNetColors[i];
|
netColors[i] = specialNetColors[i];
|
||||||
net[i].color = netColors[i];
|
net[i].color = netColors[i];
|
||||||
|
if (debugLEDs)
|
||||||
|
{
|
||||||
Serial.print("\n\r");
|
Serial.print("\n\r");
|
||||||
Serial.print(net[i].name);
|
Serial.print(net[i].name);
|
||||||
Serial.print("\t");
|
Serial.print("\t");
|
||||||
@ -108,6 +130,7 @@ void assignNetColors(void)
|
|||||||
Serial.print(netHsv.s);
|
Serial.print(netHsv.s);
|
||||||
Serial.print("\t");
|
Serial.print("\t");
|
||||||
Serial.print(netHsv.v);
|
Serial.print(netHsv.v);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int i = 0; i < 5; i++)
|
for (int i = 0; i < 5; i++)
|
||||||
@ -130,9 +153,9 @@ void assignNetColors(void)
|
|||||||
}
|
}
|
||||||
leds.show();
|
leds.show();
|
||||||
|
|
||||||
|
|
||||||
int skipSpecialColors = 0;
|
int skipSpecialColors = 0;
|
||||||
uint8_t hue = 0;
|
uint8_t hue = 8;
|
||||||
|
|
||||||
for (int i = 8; i < numberOfNets; i++)
|
for (int i = 8; i < numberOfNets; i++)
|
||||||
{
|
{
|
||||||
@ -142,7 +165,7 @@ void assignNetColors(void)
|
|||||||
|
|
||||||
int foundColor = 0;
|
int foundColor = 0;
|
||||||
|
|
||||||
for (uint8_t hueScan = ((i - 8) * colorDistance); hueScan < 255; hueScan += (colorDistance))
|
for (uint8_t hueScan = hue+(colorDistance/4) ; hueScan <= 254; hueScan += (colorDistance))
|
||||||
{
|
{
|
||||||
for (int k = 0; k < 8; k++)
|
for (int k = 0; k < 8; k++)
|
||||||
{
|
{
|
||||||
@ -150,7 +173,7 @@ void assignNetColors(void)
|
|||||||
|
|
||||||
if (hueScan > snColor.h)
|
if (hueScan > snColor.h)
|
||||||
{
|
{
|
||||||
if (hueScan - snColor.h < colorDistance)
|
if (hueScan - snColor.h < colorDistance/2)
|
||||||
{
|
{
|
||||||
skipSpecialColors = 1;
|
skipSpecialColors = 1;
|
||||||
// Serial.print("skipping special color: ");
|
// Serial.print("skipping special color: ");
|
||||||
@ -160,7 +183,7 @@ void assignNetColors(void)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else if (snColor.h - hueScan < colorDistance)
|
else if (snColor.h - hueScan < colorDistance/2)
|
||||||
{
|
{
|
||||||
skipSpecialColors = 1;
|
skipSpecialColors = 1;
|
||||||
// continue;
|
// continue;
|
||||||
@ -188,13 +211,17 @@ void assignNetColors(void)
|
|||||||
hue = hueScan;
|
hue = hueScan;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
// hue = hueScan;
|
|
||||||
|
if (i == numberOfNets && foundColor == 0)
|
||||||
|
{
|
||||||
|
//hueScan = 0;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
if (foundColor == 0)
|
if (foundColor == 0)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
hsvColor netHsv = {hue, saturation, 255};
|
hsvColor netHsv = {hue, saturation, BRIGHTNESS};
|
||||||
netColors[i] = HsvToRgb(netHsv);
|
netColors[i] = HsvToRgb(netHsv);
|
||||||
|
|
||||||
// leds.setPixelColor(i, netColors[i]);
|
// leds.setPixelColor(i, netColors[i]);
|
||||||
@ -202,20 +229,25 @@ void assignNetColors(void)
|
|||||||
net[i].color.r = netColors[i].r;
|
net[i].color.r = netColors[i].r;
|
||||||
net[i].color.g = netColors[i].g;
|
net[i].color.g = netColors[i].g;
|
||||||
net[i].color.b = netColors[i].b;
|
net[i].color.b = netColors[i].b;
|
||||||
|
if (debugLEDs)
|
||||||
|
{
|
||||||
|
|
||||||
Serial.print("\n\r");
|
Serial.print("\n\r");
|
||||||
Serial.print(net[i].name);
|
Serial.print(net[i].name);
|
||||||
Serial.print("\t\t");
|
Serial.print("\t\t");
|
||||||
Serial.print(net[i].color.r, HEX);
|
Serial.print(net[i].color.r, DEC);
|
||||||
Serial.print("\t");
|
Serial.print("\t");
|
||||||
Serial.print(net[i].color.g, HEX);
|
Serial.print(net[i].color.g, DEC);
|
||||||
Serial.print("\t");
|
Serial.print("\t");
|
||||||
Serial.print(net[i].color.b, HEX);
|
Serial.print(net[i].color.b, DEC);
|
||||||
Serial.print("\t\t");
|
Serial.print("\t\t");
|
||||||
Serial.print(hue);
|
Serial.print(hue);
|
||||||
Serial.print("\t");
|
Serial.print("\t");
|
||||||
Serial.print(saturation);
|
Serial.print(saturation);
|
||||||
Serial.print("\t");
|
Serial.print("\t");
|
||||||
Serial.print(brightness);
|
Serial.print(brightness);
|
||||||
|
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -273,6 +305,36 @@ void lightUpNode(int node)
|
|||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void lightUpRail(int rail, int onOff, int brightness2)
|
||||||
|
{
|
||||||
|
for (int j = 0; j < 4; j++)
|
||||||
|
{
|
||||||
|
if (j == rail || rail == -1)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < 5; i++)
|
||||||
|
{
|
||||||
|
|
||||||
|
if (onOff == 1)
|
||||||
|
{
|
||||||
|
uint32_t color = packRgb((railColors[j].r * brightness2) >> 8, (railColors[j].g * brightness2) >> 8, (railColors[j].b * brightness2) >> 8);
|
||||||
|
|
||||||
|
//Serial.println(color,HEX);
|
||||||
|
leds.setPixelColor(railsToPixelMap[j][i], color);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
leds.setPixelColor(railsToPixelMap[j][i], 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
leds.show();
|
||||||
|
delay(1);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
void showNets(void)
|
void showNets(void)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
@ -7,11 +7,11 @@
|
|||||||
#include "NetsToChipConnections.h"
|
#include "NetsToChipConnections.h"
|
||||||
|
|
||||||
#define LED_PIN 25
|
#define LED_PIN 25
|
||||||
#define LED_COUNT 160
|
#define LED_COUNT 80
|
||||||
#define BRIGHTNESS 50
|
#define BRIGHTNESS 120
|
||||||
|
|
||||||
extern Adafruit_NeoPixel leds;
|
extern Adafruit_NeoPixel leds;
|
||||||
|
extern bool debugLEDs;
|
||||||
typedef struct rgbColor
|
typedef struct rgbColor
|
||||||
{
|
{
|
||||||
unsigned char r;
|
unsigned char r;
|
||||||
@ -47,13 +47,14 @@ const int pixelsToRails[20] = {B_RAIL_NEG, B_RAIL_POS, B_RAIL_POS, B_RAIL_NEG, B
|
|||||||
extern rgbColor netColors[MAX_NETS];
|
extern rgbColor netColors[MAX_NETS];
|
||||||
|
|
||||||
void initLEDs(void);
|
void initLEDs(void);
|
||||||
|
void clearLEDs(void);
|
||||||
void colorWipe(uint32_t color, int wait);
|
void colorWipe(uint32_t color, int wait);
|
||||||
void rainbowy(int ,int, int wait);
|
void rainbowy(int ,int, int wait);
|
||||||
void showNets(void);
|
void showNets(void);
|
||||||
void assignNetColors (void);
|
void assignNetColors (void);
|
||||||
|
void lightUpRail (int railNumber, int onOff = 1, int brightness = BRIGHTNESS);
|
||||||
|
|
||||||
void lightUpNet (int netNumber, int node = -1, int onOff = 1, int brightness = BRIGHTNESS);//-1 means all nodes (default)
|
void lightUpNet (int netNumber = -1 , int node = -1, int onOff = 1, int brightness = BRIGHTNESS);//-1 means all nodes (default)
|
||||||
void lightUpNode (int node);
|
void lightUpNode (int node);
|
||||||
hsvColor RgbToHsv(rgbColor rgb);
|
hsvColor RgbToHsv(rgbColor rgb);
|
||||||
rgbColor HsvToRgb(hsvColor hsv);
|
rgbColor HsvToRgb(hsvColor hsv);
|
||||||
|
@ -25,6 +25,8 @@ int8_t doNotIntersectNodes[8]; //if the net tries to share a node with a net tha
|
|||||||
uint8_t priority = 0; //priority = 1 means it will move connections to take the most direct path, priority = 2 means connections will be doubled up when possible, priority = 3 means both
|
uint8_t priority = 0; //priority = 1 means it will move connections to take the most direct path, priority = 2 means connections will be doubled up when possible, priority = 3 means both
|
||||||
|
|
||||||
rgbColor color; //color of the net in hex
|
rgbColor color; //color of the net in hex
|
||||||
|
|
||||||
|
char *colorName; //name of the color
|
||||||
};
|
};
|
||||||
|
|
||||||
extern struct netStruct net[MAX_NETS];
|
extern struct netStruct net[MAX_NETS];
|
||||||
|
@ -5,6 +5,7 @@
|
|||||||
#include "MatrixStateRP2040.h"
|
#include "MatrixStateRP2040.h"
|
||||||
#include "SafeString.h"
|
#include "SafeString.h"
|
||||||
#include "NetsToChipConnections.h"
|
#include "NetsToChipConnections.h"
|
||||||
|
#include <EEPROM.h>
|
||||||
|
|
||||||
int8_t newNode1 = -1;
|
int8_t newNode1 = -1;
|
||||||
int8_t newNode2 = -1;
|
int8_t newNode2 = -1;
|
||||||
@ -22,25 +23,20 @@ int newBridge[MAX_BRIDGES][3]; // node1, node2, net
|
|||||||
int newBridgeLength = 0;
|
int newBridgeLength = 0;
|
||||||
int newBridgeIndex = 0;
|
int newBridgeIndex = 0;
|
||||||
unsigned long timeToNM;
|
unsigned long timeToNM;
|
||||||
static bool debugNM;
|
|
||||||
static bool debugNMtime;
|
bool debugNM = EEPROM.read(DEBUG_NETMANAGERADDRESS);
|
||||||
|
bool debugNMtime = EEPROM.read(TIME_NETMANAGERADDRESS);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void getNodesToConnect() // read in the nodes you'd like to connect
|
void getNodesToConnect() // read in the nodes you'd like to connect
|
||||||
{
|
{
|
||||||
timeToNM = millis();
|
timeToNM = millis();
|
||||||
if (DEBUG_NETMANAGER == 1)
|
|
||||||
debugNM = true;
|
|
||||||
else
|
|
||||||
debugNM = false;
|
|
||||||
if (TIME_NETMANAGER == 1)
|
|
||||||
debugNMtime = true;
|
|
||||||
else
|
|
||||||
debugNMtime = false;
|
|
||||||
|
|
||||||
if (debugNM)
|
if (debugNM)
|
||||||
Serial.println("\n\n\rconnecting nodes into nets\n\r");
|
Serial.println("\n\n\rconnecting nodes into nets\n\r");
|
||||||
|
|
||||||
newBridgeIndex = 0;
|
//newBridgeIndex = 0;
|
||||||
for (int i = 0; i < newBridgeLength; i++)
|
for (int i = 0; i < newBridgeLength; i++)
|
||||||
{
|
{
|
||||||
newNode1 = path[i].node1;
|
newNode1 = path[i].node1;
|
||||||
@ -58,7 +54,7 @@ void getNodesToConnect() // read in the nodes you'd like to connect
|
|||||||
|
|
||||||
// do some error checking
|
// do some error checking
|
||||||
|
|
||||||
if (newNode1 == 0 || newNode2 == 0)
|
if (newNode1 <= 0 || newNode2 <= 0)
|
||||||
{
|
{
|
||||||
path[i].net = -1;
|
path[i].net = -1;
|
||||||
}
|
}
|
||||||
@ -72,11 +68,13 @@ void getNodesToConnect() // read in the nodes you'd like to connect
|
|||||||
// if (i < 7)
|
// if (i < 7)
|
||||||
// {
|
// {
|
||||||
if (debugNM)
|
if (debugNM)
|
||||||
listSpecialNets();
|
//listSpecialNets();
|
||||||
// }
|
// }
|
||||||
|
|
||||||
if (debugNM)
|
if (debugNM)
|
||||||
listNets();
|
{
|
||||||
|
//listNets();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
if (debugNM)
|
if (debugNM)
|
||||||
Serial.println("done");
|
Serial.println("done");
|
||||||
@ -95,14 +93,14 @@ int searchExistingNets(int node1, int node2) // search through existing nets for
|
|||||||
|
|
||||||
for (int i = 1; i < MAX_NETS; i++)
|
for (int i = 1; i < MAX_NETS; i++)
|
||||||
{
|
{
|
||||||
if (net[i].number == 0) // stops searching if it gets to an unallocated net
|
if (net[i].number <= 0) // stops searching if it gets to an unallocated net
|
||||||
{
|
{
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int j = 0; j < MAX_NODES; j++)
|
for (int j = 0; j < MAX_NODES; j++)
|
||||||
{
|
{
|
||||||
if (net[i].nodes[j] == 0)
|
if (net[i].nodes[j] <= 0)
|
||||||
{
|
{
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -457,8 +455,9 @@ void addNodeToNet(int netToAddNode, int node)
|
|||||||
if (debugNM)
|
if (debugNM)
|
||||||
Serial.print(netToAddNode);
|
Serial.print(netToAddNode);
|
||||||
if (debugNM)
|
if (debugNM)
|
||||||
Serial.print(", skipping\n\r");
|
Serial.print(", still adding to net\n\r");
|
||||||
return;
|
return;
|
||||||
|
//break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -469,7 +468,7 @@ int findFirstUnusedNetIndex() // search for a free net[]
|
|||||||
{
|
{
|
||||||
for (int i = 0; i < MAX_NETS; i++)
|
for (int i = 0; i < MAX_NETS; i++)
|
||||||
{
|
{
|
||||||
if (net[i].nodes[0] == 0)
|
if (net[i].nodes[0] <= 0)
|
||||||
{
|
{
|
||||||
if (debugNM)
|
if (debugNM)
|
||||||
Serial.print("found unused Net ");
|
Serial.print("found unused Net ");
|
||||||
@ -626,17 +625,17 @@ void listNets(void) // list nets doesnt care about debugNM, don't call it if you
|
|||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
Serial.print("\n\rIndex\tName\t\tNumber\t\tNodes\t\t\tBridges\t\t\t\tDo Not Intersects");
|
Serial.print("\n\rIndex\tName\t\tNumber\t\tNodes\t\t\tBridges\t\t\t\tColor\t\tDo Not Intersects");
|
||||||
|
|
||||||
int tabs = 0;
|
int tabs = 0;
|
||||||
for (int i = 8; i < MAX_NETS; i++)
|
for (int i = 8; i < MAX_NETS; i++)
|
||||||
{
|
{
|
||||||
if (net[i].number == 0) // stops searching if it gets to an unallocated net
|
if (net[i].number == 0 || net[i].nodes[0] == -1) // stops searching if it gets to an unallocated net
|
||||||
{
|
{
|
||||||
// Serial.print("Done listing nets");
|
// Serial.print("Done listing nets");
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
Serial.print("\n\r");
|
Serial.print("\n\r");
|
||||||
Serial.print(i);
|
Serial.print(i);
|
||||||
Serial.print("\t");
|
Serial.print("\t");
|
||||||
@ -644,7 +643,7 @@ void listNets(void) // list nets doesnt care about debugNM, don't call it if you
|
|||||||
Serial.print("\t\t");
|
Serial.print("\t\t");
|
||||||
Serial.print(net[i].number);
|
Serial.print(net[i].number);
|
||||||
Serial.print("\t\t");
|
Serial.print("\t\t");
|
||||||
|
|
||||||
tabs = 0;
|
tabs = 0;
|
||||||
for (int j = 0; j < MAX_NODES; j++)
|
for (int j = 0; j < MAX_NODES; j++)
|
||||||
{
|
{
|
||||||
@ -694,6 +693,9 @@ void listNets(void) // list nets doesnt care about debugNM, don't call it if you
|
|||||||
{
|
{
|
||||||
Serial.print("\t");
|
Serial.print("\t");
|
||||||
}
|
}
|
||||||
|
/*
|
||||||
|
Serial.print(net[i].colorName);
|
||||||
|
Serial.print("\t\t");
|
||||||
|
|
||||||
for (int j = 0; j < MAX_DNI; j++)
|
for (int j = 0; j < MAX_DNI; j++)
|
||||||
{
|
{
|
||||||
@ -710,14 +712,15 @@ void listNets(void) // list nets doesnt care about debugNM, don't call it if you
|
|||||||
tabs += Serial.print(",");
|
tabs += Serial.print(",");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
*/
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
Serial.print("\n\n\n\r");
|
Serial.print("\n\r");
|
||||||
}
|
}
|
||||||
|
|
||||||
void listSpecialNets()
|
void listSpecialNets()
|
||||||
{
|
{
|
||||||
Serial.print("\n\rIndex\tName\t\tNumber\t\tNodes\t\t\tBridges\t\t\t\tDo Not Intersects");
|
Serial.print("\n\rIndex\tName\t\tNumber\t\tNodes\t\t\tBridges");//\t\t\t\tColor\t\tDo Not Intersects");
|
||||||
int tabs = 0;
|
int tabs = 0;
|
||||||
for (int i = 0; i < 8; i++)
|
for (int i = 0; i < 8; i++)
|
||||||
{
|
{
|
||||||
@ -784,6 +787,9 @@ void listSpecialNets()
|
|||||||
{
|
{
|
||||||
Serial.print("\t");
|
Serial.print("\t");
|
||||||
}
|
}
|
||||||
|
/*
|
||||||
|
Serial.print(net[i].colorName);
|
||||||
|
Serial.print("\t\t");
|
||||||
|
|
||||||
for (int j = 0; j < MAX_DNI; j++)
|
for (int j = 0; j < MAX_DNI; j++)
|
||||||
{
|
{
|
||||||
@ -799,7 +805,7 @@ void listSpecialNets()
|
|||||||
|
|
||||||
tabs += Serial.print(",");
|
tabs += Serial.print(",");
|
||||||
}
|
}
|
||||||
}
|
}*/
|
||||||
}
|
}
|
||||||
Serial.print("\n\r");
|
Serial.print("\n\r");
|
||||||
}
|
}
|
||||||
@ -836,7 +842,7 @@ void printBridgeArray(void)
|
|||||||
}
|
}
|
||||||
tabs = 0;
|
tabs = 0;
|
||||||
|
|
||||||
if (lineCount == 5)
|
if (lineCount == 4)
|
||||||
{
|
{
|
||||||
Serial.print("\n\r");
|
Serial.print("\n\r");
|
||||||
lineCount = 0;
|
lineCount = 0;
|
||||||
@ -899,6 +905,23 @@ const char *definesToChar(int defined) // converts the internally used #defined
|
|||||||
return same;
|
return same;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void clearAllPaths (void)
|
||||||
|
{
|
||||||
|
digitalWrite(RESETPIN, HIGH);
|
||||||
|
delay(1);
|
||||||
|
digitalWrite(RESETPIN, LOW);
|
||||||
|
|
||||||
|
for (int i = 0; i < MAX_BRIDGES; i++)
|
||||||
|
{
|
||||||
|
path[i].node1 = 0;
|
||||||
|
path[i].node2 = 0;
|
||||||
|
path[i].net = 0;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
/*
|
/*
|
||||||
|
|
||||||
|
|
||||||
|
@ -9,7 +9,8 @@
|
|||||||
extern int newBridge[MAX_BRIDGES][3]; // node1, node2, net
|
extern int newBridge[MAX_BRIDGES][3]; // node1, node2, net
|
||||||
extern int newBridgeLength;
|
extern int newBridgeLength;
|
||||||
extern int newBridgeIndex;
|
extern int newBridgeIndex;
|
||||||
|
extern bool debugNM;
|
||||||
|
extern bool debugNMtime;
|
||||||
|
|
||||||
|
|
||||||
void writeJSONtoFile();
|
void writeJSONtoFile();
|
||||||
|
File diff suppressed because it is too large
Load Diff
@ -9,6 +9,11 @@ extern int numberOfUniqueNets;
|
|||||||
extern int numberOfNets;
|
extern int numberOfNets;
|
||||||
extern int numberOfPaths;
|
extern int numberOfPaths;
|
||||||
|
|
||||||
|
extern bool debugNTCC;
|
||||||
|
extern bool debugNTCC2;
|
||||||
|
|
||||||
|
void clearAllNTCC(void);
|
||||||
|
|
||||||
void sortPathsByNet(void);
|
void sortPathsByNet(void);
|
||||||
void bridgesToPaths(void);
|
void bridgesToPaths(void);
|
||||||
|
|
||||||
|
@ -18,7 +18,7 @@
|
|||||||
|
|
||||||
#define DAC_RESOLUTION 9
|
#define DAC_RESOLUTION 9
|
||||||
|
|
||||||
uint16_t freq[3] = {1, 1, 0};
|
float freq[3] = {1, 1, 0};
|
||||||
uint32_t period[3] = {0, 0, 0};
|
uint32_t period[3] = {0, 0, 0};
|
||||||
uint32_t halvePeriod[3] = {0, 0, 0};
|
uint32_t halvePeriod[3] = {0, 0, 0};
|
||||||
|
|
||||||
@ -223,7 +223,7 @@ void refillTable(int amplitude, int offset, int dac)
|
|||||||
//int offsetCorr = 0;
|
//int offsetCorr = 0;
|
||||||
if (dac == 0)
|
if (dac == 0)
|
||||||
{
|
{
|
||||||
offset = amplitude / 2;
|
//offset = amplitude / 2;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int i = 0; i < 360; i++)
|
for (int i = 0; i < 360; i++)
|
||||||
@ -307,7 +307,7 @@ void waveGen(void)
|
|||||||
mode[2] = 's';
|
mode[2] = 's';
|
||||||
int dacOn[3] = {0, 0, 0};
|
int dacOn[3] = {0, 0, 0};
|
||||||
int amplitude[3] = {4095, 4140, 0};
|
int amplitude[3] = {4095, 4140, 0};
|
||||||
int offset[3] = {1, 1932, 2047};
|
int offset[3] = {2047, 1932, 2047};
|
||||||
int calib[3] = {-10, 100, 0};
|
int calib[3] = {-10, 100, 0};
|
||||||
|
|
||||||
|
|
||||||
@ -323,11 +323,11 @@ void waveGen(void)
|
|||||||
Serial.println("\ta = set amplitude (p-p)\tw = sawtooth\t\t* = frequency*2\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("\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("\tv = voltage\t\tr = random\t\t \n\r");
|
||||||
Serial.println("\th = show this menu\t\t\t \n\r");
|
Serial.println("\th = show this menu\tx = exit\t\t \n\r");
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
period[activeDac] = 1e6 / freq[activeDac];
|
period[activeDac] = 1e6 / (freq[activeDac]/10);
|
||||||
halvePeriod[activeDac] = period[activeDac] / 2;
|
halvePeriod[activeDac] = period[activeDac] / 2;
|
||||||
int chars = 0;
|
int chars = 0;
|
||||||
|
|
||||||
@ -376,10 +376,25 @@ chars += Serial.print(adc0Reading);
|
|||||||
switch (c)
|
switch (c)
|
||||||
{
|
{
|
||||||
case '+':
|
case '+':
|
||||||
|
if (freq[activeDac] >= 1.0)
|
||||||
|
{
|
||||||
|
|
||||||
freq[activeDac]++;
|
freq[activeDac]++;
|
||||||
|
} else {
|
||||||
|
freq[activeDac] += 0.1;
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
case '-':
|
case '-':
|
||||||
|
|
||||||
|
if (freq[activeDac] > 1.0)
|
||||||
|
{
|
||||||
freq[activeDac]--;
|
freq[activeDac]--;
|
||||||
|
} else if (freq[activeDac] > 0.1){
|
||||||
|
freq[activeDac] -= 0.1;
|
||||||
|
} else {
|
||||||
|
freq[activeDac] = 0.0;
|
||||||
|
}
|
||||||
|
|
||||||
break;
|
break;
|
||||||
case '*':
|
case '*':
|
||||||
freq[activeDac] *= 2;
|
freq[activeDac] *= 2;
|
||||||
@ -457,6 +472,9 @@ chars += Serial.print(adc0Reading);
|
|||||||
|
|
||||||
mode[activeDac] = c;
|
mode[activeDac] = c;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case 'x':
|
||||||
|
return;
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -538,9 +556,9 @@ chars += Serial.print(adc0Reading);
|
|||||||
{
|
{
|
||||||
|
|
||||||
if (t < halvePeriod[activeDac])
|
if (t < halvePeriod[activeDac])
|
||||||
dac0_5V.setValue(t * amplitude[activeDac] / halvePeriod[activeDac]);
|
dac0_5V.setValue(((t * amplitude[activeDac]) / halvePeriod[activeDac] )+ offset[activeDac]);
|
||||||
else
|
else
|
||||||
dac0_5V.setValue((period[activeDac] - t) * amplitude[activeDac] / halvePeriod[activeDac]);
|
dac0_5V.setValue((((period[activeDac] - t) * (amplitude[activeDac]) / halvePeriod[activeDac])+offset[activeDac]));
|
||||||
}
|
}
|
||||||
else if (activeDac == 1 && dacOn[activeDac] == 1)
|
else if (activeDac == 1 && dacOn[activeDac] == 1)
|
||||||
{
|
{
|
||||||
@ -565,13 +583,13 @@ chars += Serial.print(adc0Reading);
|
|||||||
dac1_8V.setValue(offset[activeDac]);
|
dac1_8V.setValue(offset[activeDac]);
|
||||||
break;
|
break;
|
||||||
case 'h': // high
|
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("\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("\t5/0 = dac 0 0-5V (togg)\tq = square\t\t+ = frequency++\n\r");
|
||||||
Serial.println("\t8 = dac 1 +-8V (toggle)\ts = sine\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\tw = sawtooth\t\t* = frequency*2\n\r");
|
Serial.println("\ta = set amplitude (p-p)\tw = sawtooth\t\t* = frequency*2\n\r");
|
||||||
Serial.println("\to = set offset\t\tt = stair\t\t/ = frequency/2\n\r");
|
Serial.println("\to = set offset\t\tt = triangle\t\t/ = frequency/2\n\r");
|
||||||
Serial.println("\tv = voltageGen menu\tr = random\t\t0-9 = frequency_\n\r");
|
Serial.println("\tv = voltage\t\tr = random\t\t \n\r");
|
||||||
Serial.println("\th = show this menu\tz = triangle\t\tc = frequency = 0\n\r");
|
Serial.println("\th = show this menu\tx = exit\t\t \n\r");
|
||||||
mode[activeDac] = mode[2];
|
mode[activeDac] = mode[2];
|
||||||
break;
|
break;
|
||||||
case 'm': // mid
|
case 'm': // mid
|
||||||
@ -606,6 +624,15 @@ chars += Serial.print(adc0Reading);
|
|||||||
while (Serial.available() == 0)
|
while (Serial.available() == 0)
|
||||||
;
|
;
|
||||||
a = Serial.read();
|
a = Serial.read();
|
||||||
|
|
||||||
|
if (a == '.')
|
||||||
|
{
|
||||||
|
while (Serial.available() == 0)
|
||||||
|
;
|
||||||
|
|
||||||
|
a = Serial.read();
|
||||||
|
}
|
||||||
|
|
||||||
if (a >= 48 && a <= 57)
|
if (a >= 48 && a <= 57)
|
||||||
{
|
{
|
||||||
Serial.print((char)a);
|
Serial.print((char)a);
|
||||||
@ -638,7 +665,7 @@ chars += Serial.print(adc0Reading);
|
|||||||
while (Serial.available() == 0)
|
while (Serial.available() == 0)
|
||||||
;
|
;
|
||||||
aC = Serial.read();
|
aC = Serial.read();
|
||||||
if (aC == 'a')
|
if (aC == 'o')
|
||||||
aC = Serial.read();
|
aC = Serial.read();
|
||||||
a = aC;
|
a = aC;
|
||||||
|
|
||||||
@ -658,6 +685,7 @@ chars += Serial.print(adc0Reading);
|
|||||||
{
|
{
|
||||||
while (Serial.available() == 0)
|
while (Serial.available() == 0)
|
||||||
;
|
;
|
||||||
|
|
||||||
a = Serial.read();
|
a = Serial.read();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -690,7 +718,7 @@ chars += Serial.print(adc0Reading);
|
|||||||
int newOffset = 0;
|
int newOffset = 0;
|
||||||
int input = 0;
|
int input = 0;
|
||||||
char aC = 0;
|
char aC = 0;
|
||||||
int a = 0;
|
int o = 0;
|
||||||
if (activeDac == 0)
|
if (activeDac == 0)
|
||||||
{
|
{
|
||||||
|
|
||||||
@ -698,25 +726,37 @@ chars += Serial.print(adc0Reading);
|
|||||||
while (Serial.available() == 0)
|
while (Serial.available() == 0)
|
||||||
;
|
;
|
||||||
aC = Serial.read();
|
aC = Serial.read();
|
||||||
if (aC == 'a')
|
if (aC == 'o')
|
||||||
aC = Serial.read();
|
aC = Serial.read();
|
||||||
a = aC;
|
|
||||||
|
o = aC;
|
||||||
|
|
||||||
Serial.print(aC);
|
Serial.print(aC);
|
||||||
|
|
||||||
if (a >= 48 && a <= 53)
|
|
||||||
|
if (o >= 48 && o <= 53)
|
||||||
{
|
{
|
||||||
|
|
||||||
input = a - 48;
|
input = o - 48;
|
||||||
newOffset = input * 819;
|
newOffset = input * 819;
|
||||||
Serial.print(".");
|
Serial.print(".");
|
||||||
while (Serial.available() == 0)
|
while (Serial.available() == 0)
|
||||||
;
|
;
|
||||||
a = Serial.read();
|
o = Serial.read();
|
||||||
if (a >= 48 && a <= 57)
|
|
||||||
|
if (o == '.')
|
||||||
{
|
{
|
||||||
Serial.print((char)a);
|
while (Serial.available() == 0)
|
||||||
input = a - 48;
|
;
|
||||||
|
|
||||||
|
o = Serial.read();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
if (o >= 48 && o <= 57)
|
||||||
|
{
|
||||||
|
Serial.print((char)o);
|
||||||
|
input = o - 48;
|
||||||
newOffset += input * 81.9;
|
newOffset += input * 81.9;
|
||||||
|
|
||||||
offset[activeDac] = newOffset;
|
offset[activeDac] = newOffset;
|
||||||
@ -748,14 +788,14 @@ chars += Serial.print(adc0Reading);
|
|||||||
aC = Serial.read();
|
aC = Serial.read();
|
||||||
}
|
}
|
||||||
|
|
||||||
a = aC;
|
o = aC;
|
||||||
|
|
||||||
Serial.print(aC);
|
Serial.print(aC);
|
||||||
|
|
||||||
if (a >= 48 && a <= 55)
|
if (o >= 48 && o <= 55)
|
||||||
{
|
{
|
||||||
|
|
||||||
input = a - 48;
|
input = o - 48;
|
||||||
newOffset = input * 276;
|
newOffset = input * 276;
|
||||||
|
|
||||||
if (input == '7')
|
if (input == '7')
|
||||||
@ -768,18 +808,18 @@ chars += Serial.print(adc0Reading);
|
|||||||
Serial.print(".");
|
Serial.print(".");
|
||||||
while (Serial.available() == 0)
|
while (Serial.available() == 0)
|
||||||
;
|
;
|
||||||
a = Serial.read();
|
o = Serial.read();
|
||||||
if (a == '.')
|
if (o == '.')
|
||||||
{
|
{
|
||||||
while (Serial.available() == 0)
|
while (Serial.available() == 0)
|
||||||
;
|
;
|
||||||
a = Serial.read();
|
o = Serial.read();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (a >= 48 && a <= 57)
|
if (o >= 48 && o <= 57)
|
||||||
{
|
{
|
||||||
Serial.print((char)a);
|
Serial.print((char)o);
|
||||||
input = a - 48;
|
input = o - 48;
|
||||||
newOffset += input * 27.6;
|
newOffset += input * 27.6;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -10,60 +10,349 @@
|
|||||||
#include "Peripherals.h"
|
#include "Peripherals.h"
|
||||||
#include <Wire.h>
|
#include <Wire.h>
|
||||||
#include <Adafruit_MCP4725.h>
|
#include <Adafruit_MCP4725.h>
|
||||||
|
#include <EEPROM.h>
|
||||||
|
|
||||||
|
//https://wokwi.com/projects/367384677537829889
|
||||||
|
|
||||||
|
|
||||||
// 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
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
|
EEPROM.begin(256);
|
||||||
|
|
||||||
|
debugFlagInit();
|
||||||
initCH446Q();
|
initCH446Q();
|
||||||
initADC();
|
initADC();
|
||||||
initDAC();
|
initDAC();
|
||||||
initINA219();
|
initINA219();
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
|
|
||||||
initLEDs();
|
initLEDs();
|
||||||
LittleFS.begin();
|
LittleFS.begin();
|
||||||
//delay(3000);
|
|
||||||
//rainbowy(255,253,100);
|
|
||||||
parseWokwiFileToNodeFile();
|
|
||||||
openNodeFile();
|
|
||||||
//while(1);
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
lightUpRail(-1, 1, 220);
|
||||||
|
|
||||||
|
if (EEPROM.read(CLEARBEFORECOMMANDADDRESS) == 0)
|
||||||
|
{
|
||||||
|
|
||||||
|
if (LittleFS.exists("/nodeFile.txt"))
|
||||||
|
{
|
||||||
|
delay(20);
|
||||||
|
openNodeFile();
|
||||||
|
getNodesToConnect();
|
||||||
|
|
||||||
|
Serial.println("\n\n\rnetlist\n\n\r");
|
||||||
|
|
||||||
|
bridgesToPaths();
|
||||||
|
|
||||||
|
listSpecialNets();
|
||||||
|
listNets();
|
||||||
|
printBridgeArray();
|
||||||
|
Serial.print("\n\n\r");
|
||||||
|
Serial.print(numberOfNets);
|
||||||
|
|
||||||
|
Serial.print("\n\n\r");
|
||||||
|
Serial.print(numberOfPaths);
|
||||||
|
|
||||||
|
assignNetColors();
|
||||||
|
|
||||||
|
sendAllPaths();
|
||||||
|
} else {
|
||||||
|
while (Serial.available() > 0)
|
||||||
|
{
|
||||||
|
Serial.read();
|
||||||
|
delay(1);
|
||||||
|
}
|
||||||
|
|
||||||
|
delay(20);
|
||||||
|
}
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
delay(20);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// rainbowy(255,253,100);
|
||||||
|
// parseWokwiFileToNodeFile();
|
||||||
|
//openNodeFile();
|
||||||
|
// while(1);
|
||||||
|
lastCommandRead();
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
|
|
||||||
getNodesToConnect();
|
// getNodesToConnect();
|
||||||
|
// bridgesToPaths();
|
||||||
|
// assignNetColors();
|
||||||
|
|
||||||
|
// sendAllPaths();
|
||||||
|
|
||||||
|
// examples
|
||||||
|
|
||||||
|
// add connection
|
||||||
|
char input;
|
||||||
|
unsigned long timer = 0;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
menu:
|
||||||
|
Serial.print("\n\n\r\t\t\tMenu\n\n\r");
|
||||||
|
Serial.print("\tn = show netlist\n\r");
|
||||||
|
Serial.print("\tb = show bridge array\n\r");
|
||||||
|
Serial.print("\tw = waveGen\n\r");
|
||||||
|
Serial.print("\tm = measure current/voltage\n\r");
|
||||||
|
Serial.print("\tf = load formatted nodeFile\n\r");
|
||||||
|
Serial.print("\tu = upload new Wokwi diagram\n\r");
|
||||||
|
Serial.print("\tt = reset and load nodeFile.txt\n\r");
|
||||||
|
Serial.print("\td = toggle debug flags\n\r");
|
||||||
|
Serial.print("\tr = reset\n\r");
|
||||||
|
Serial.print("\n\r");
|
||||||
|
|
||||||
|
if (EEPROM.read(CLEARBEFORECOMMANDADDRESS) == 1)
|
||||||
|
{
|
||||||
|
|
||||||
|
input = EEPROM.read(LASTCOMMANDADDRESS);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
while (Serial.available() == 0)
|
||||||
|
;
|
||||||
|
|
||||||
|
input = Serial.read();
|
||||||
|
}
|
||||||
|
if (input != 'l')
|
||||||
|
{
|
||||||
|
lastCommandWrite(input);
|
||||||
|
}
|
||||||
|
|
||||||
|
Serial.print(input);
|
||||||
|
Serial.print("\n\r");
|
||||||
|
|
||||||
|
switch (input)
|
||||||
|
{
|
||||||
|
case 'l':
|
||||||
|
lastCommandRead();
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 'n':
|
||||||
|
lastCommandWrite(input);
|
||||||
|
Serial.print("\n\n\rnetlist\n\n\r");
|
||||||
|
listSpecialNets();
|
||||||
|
listNets();
|
||||||
|
break;
|
||||||
|
case 'b':
|
||||||
|
lastCommandWrite(input);
|
||||||
|
printBridgeArray();
|
||||||
|
break;
|
||||||
|
case 'w':
|
||||||
|
lastCommandWrite(input);
|
||||||
|
waveGen();
|
||||||
|
break;
|
||||||
|
case 'm':
|
||||||
|
// measureCurrent();
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 'f':
|
||||||
|
digitalWrite(RESETPIN, HIGH);
|
||||||
|
|
||||||
|
|
||||||
|
clearAllNTCC();
|
||||||
|
clearLEDs();
|
||||||
|
digitalWrite(RESETPIN, LOW);
|
||||||
|
|
||||||
|
timer = millis();
|
||||||
|
savePreformattedNodeFile ();
|
||||||
|
|
||||||
|
openNodeFile();
|
||||||
|
getNodesToConnect();
|
||||||
|
|
||||||
|
bridgesToPaths();
|
||||||
|
assignNetColors();
|
||||||
|
|
||||||
Serial.println("\n\n\rfinal netlist\n\n\r");
|
|
||||||
listSpecialNets();
|
|
||||||
listNets();
|
|
||||||
printBridgeArray();
|
|
||||||
//rainbowy(255,30,100);
|
|
||||||
bridgesToPaths();
|
|
||||||
assignNetColors();
|
|
||||||
//showNets();
|
|
||||||
|
|
||||||
//delay(3000);
|
|
||||||
sendAllPaths();
|
sendAllPaths();
|
||||||
|
|
||||||
int i = 0;
|
|
||||||
|
Serial.print("\n\n\r");
|
||||||
|
Serial.print("took ");
|
||||||
|
Serial.print(millis() - timer);
|
||||||
|
Serial.print("ms");
|
||||||
|
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 'u':
|
||||||
|
|
||||||
|
//case '{':
|
||||||
|
|
||||||
|
|
||||||
|
digitalWrite(RESETPIN, HIGH);
|
||||||
|
delay(1);
|
||||||
|
//clearNodeFile();
|
||||||
|
digitalWrite(RESETPIN, LOW);
|
||||||
|
clearAllNTCC();
|
||||||
|
clearLEDs();
|
||||||
|
|
||||||
|
|
||||||
|
//EEPROM.write(CLEARBEFORECOMMANDADDRESS, 0);
|
||||||
|
//EEPROM.commit();
|
||||||
|
|
||||||
|
timer = millis();
|
||||||
|
//savePreformattedNodeFile ();
|
||||||
|
parseWokwiFileToNodeFile();
|
||||||
|
//lastCommandWrite(input);
|
||||||
|
openNodeFile();
|
||||||
|
getNodesToConnect();
|
||||||
|
|
||||||
|
Serial.println("\n\n\rnetlist\n\n\r");
|
||||||
|
// listSpecialNets();
|
||||||
|
// listNets();
|
||||||
|
// printBridgeArray();
|
||||||
|
|
||||||
|
bridgesToPaths();
|
||||||
|
assignNetColors();
|
||||||
|
|
||||||
|
sendAllPaths();
|
||||||
|
|
||||||
|
|
||||||
|
Serial.print("\n\n\r");
|
||||||
|
Serial.print("took ");
|
||||||
|
Serial.print(millis() - timer);
|
||||||
|
Serial.print("ms");
|
||||||
|
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 't':
|
||||||
|
clearNodeFile();
|
||||||
|
lastCommandWrite(input);
|
||||||
|
|
||||||
|
runCommandAfterReset('t');
|
||||||
|
|
||||||
|
|
||||||
|
openNodeFile();
|
||||||
|
getNodesToConnect();
|
||||||
|
|
||||||
|
Serial.println("\n\n\rnetlist\n\n\r");
|
||||||
|
|
||||||
|
bridgesToPaths();
|
||||||
|
|
||||||
|
listSpecialNets();
|
||||||
|
listNets();
|
||||||
|
printBridgeArray();
|
||||||
|
Serial.print("\n\n\r");
|
||||||
|
Serial.print(numberOfNets);
|
||||||
|
|
||||||
|
Serial.print("\n\n\r");
|
||||||
|
Serial.print(numberOfPaths);
|
||||||
|
|
||||||
|
assignNetColors();
|
||||||
|
|
||||||
|
sendAllPaths();
|
||||||
|
|
||||||
|
EEPROM.write(CLEARBEFORECOMMANDADDRESS, 0);
|
||||||
|
EEPROM.commit();
|
||||||
|
break;
|
||||||
|
|
||||||
|
case 'r':
|
||||||
|
EEPROM.commit();
|
||||||
|
digitalWrite(RESETPIN, HIGH);
|
||||||
|
delay(1);
|
||||||
|
clearNodeFile();
|
||||||
|
digitalWrite(RESETPIN, LOW);
|
||||||
|
clearAllNTCC();
|
||||||
|
leds.clear();
|
||||||
|
leds.show();
|
||||||
|
|
||||||
|
AIRCR_Register = 0x5FA0004; // this just hardware resets the rp2040, it would be too much of a pain in the ass to reinitialize everything
|
||||||
|
|
||||||
|
break;
|
||||||
|
/*
|
||||||
|
case '{':
|
||||||
|
|
||||||
|
lastCommandWrite(input);
|
||||||
|
|
||||||
|
runCommandAfterReset('u');
|
||||||
|
|
||||||
|
//lastCommandWrite('{');
|
||||||
|
parseWokwiFileToNodeFile();
|
||||||
|
getNodesToConnect();
|
||||||
|
|
||||||
|
Serial.println("\n\n\rnetlist\n\r");
|
||||||
|
listSpecialNets();
|
||||||
|
listNets();
|
||||||
|
// printBridgeArray();
|
||||||
|
|
||||||
|
bridgesToPaths();
|
||||||
|
assignNetColors();
|
||||||
|
|
||||||
|
sendAllPaths();
|
||||||
|
|
||||||
|
EEPROM.write(CLEARBEFORECOMMANDADDRESS, 0);
|
||||||
|
EEPROM.commit();
|
||||||
|
break;
|
||||||
|
*/
|
||||||
|
case 'd':
|
||||||
|
debugFlagInit();
|
||||||
|
lastCommandWrite(input);
|
||||||
|
{
|
||||||
|
debugFlags:
|
||||||
|
Serial.print("\n\r0. all off");
|
||||||
|
Serial.print("\n\r9. all on");
|
||||||
|
Serial.print("\n\ra-z. exit\n\r");
|
||||||
|
|
||||||
|
Serial.print("\n\r1. file parsing = ");
|
||||||
|
Serial.print(debugFP);
|
||||||
|
Serial.print("\n\r2. file parsing time = ");
|
||||||
|
Serial.print(debugFPtime);
|
||||||
|
|
||||||
|
Serial.print("\n\r3. net manager = ");
|
||||||
|
Serial.print(debugNM);
|
||||||
|
Serial.print("\n\r4. net manager time = ");
|
||||||
|
Serial.print(debugNMtime);
|
||||||
|
|
||||||
|
Serial.print("\n\r5. chip connections = ");
|
||||||
|
Serial.print(debugNTCC);
|
||||||
|
Serial.print("\n\r6. chip conns alt paths = ");
|
||||||
|
Serial.print(debugNTCC2);
|
||||||
|
Serial.print("\n\r7. LEDs = ");
|
||||||
|
Serial.print(debugLEDs);
|
||||||
|
|
||||||
|
Serial.print("\n\n\r");
|
||||||
|
|
||||||
|
while (Serial.available() == 0)
|
||||||
|
;
|
||||||
|
|
||||||
|
int toggleDebug = Serial.read();
|
||||||
|
toggleDebug -= '0';
|
||||||
|
|
||||||
|
if (toggleDebug >= 0 && toggleDebug <= 9)
|
||||||
|
{
|
||||||
|
debugFlagSet(toggleDebug);
|
||||||
|
goto debugFlags;
|
||||||
|
} else {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
default:
|
||||||
|
while (Serial.available() > 0)
|
||||||
|
{
|
||||||
|
int f = Serial.read();
|
||||||
|
delayMicroseconds(100);
|
||||||
|
}
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
goto menu;
|
||||||
|
|
||||||
while (1)
|
while (1)
|
||||||
{
|
{
|
||||||
//sendAllPaths();
|
|
||||||
|
|
||||||
//dacSine(1);
|
// waveGen();
|
||||||
|
|
||||||
//setDac0_5V(3.3);
|
|
||||||
waveGen();
|
|
||||||
//
|
|
||||||
//dacTriangle();
|
|
||||||
//delay(1200);
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user