mirror of
https://github.com/Architeuthis-Flux/Jumperless.git
synced 2025-02-25 14:24:49 +01:00
Upgraded Wokwi bridge
The new bridge app passes the serial data through to the terminal window
This commit is contained in:
parent
76ec3e44dc
commit
b8f58bc7ff
Binary file not shown.
@ -5,14 +5,32 @@ import requests
|
|||||||
import json
|
import json
|
||||||
import serial
|
import serial
|
||||||
import time
|
import time
|
||||||
|
import runpy
|
||||||
|
import subprocess
|
||||||
|
import sys
|
||||||
|
import codecs
|
||||||
#import pyduinocli
|
#import pyduinocli
|
||||||
|
|
||||||
import serial.tools.list_ports
|
#from watchedserial import WatchedReaderThread
|
||||||
debug = True
|
|
||||||
|
|
||||||
|
import serial.tools.list_ports
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
debug = False
|
||||||
|
|
||||||
|
|
||||||
|
justreconnected = 0
|
||||||
|
|
||||||
|
global serialconnected
|
||||||
|
serialconnected = 0
|
||||||
|
|
||||||
portSelected = 0
|
portSelected = 0
|
||||||
|
|
||||||
|
stringified = 0
|
||||||
|
lastDiagram = 1
|
||||||
|
|
||||||
|
|
||||||
print("\n\r")
|
print("\n\r")
|
||||||
|
|
||||||
while portSelected == False:
|
while portSelected == False:
|
||||||
@ -20,8 +38,8 @@ while portSelected == False:
|
|||||||
ports = serial.tools.list_ports.comports()
|
ports = serial.tools.list_ports.comports()
|
||||||
i = 0
|
i = 0
|
||||||
for port, desc, hwid in ports:
|
for port, desc, hwid in ports:
|
||||||
i = i + 1
|
i = i + 1
|
||||||
print("{}: {} [{}]".format(i, port, desc))
|
print("{}: {} [{}]".format(i, port, desc))
|
||||||
|
|
||||||
selection = input ("\n\n\rSelect the port connected to your Jumperless ('r' to rescan)\n\n\r")
|
selection = input ("\n\n\rSelect the port connected to your Jumperless ('r' to rescan)\n\n\r")
|
||||||
#selection = "3"
|
#selection = "3"
|
||||||
@ -29,230 +47,544 @@ while portSelected == False:
|
|||||||
portName = ports[int(selection) - 1].device
|
portName = ports[int(selection) - 1].device
|
||||||
portSelected = True
|
portSelected = True
|
||||||
print(ports[int(selection) - 1].device)
|
print(ports[int(selection) - 1].device)
|
||||||
|
serialconnected = 1
|
||||||
#print(0 in ports)
|
#print(0 in ports)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#portName = '/dev/cu.usbmodem11301'
|
#portName = '/dev/cu.usbmodem11301'
|
||||||
|
|
||||||
|
ser = serial.Serial(portName, 115200, timeout = None )
|
||||||
|
|
||||||
def portIsUsable(portName):
|
justChecked = 0
|
||||||
try:
|
reading = 0
|
||||||
ser = serial.Serial(port=portName)
|
|
||||||
return False
|
|
||||||
except:
|
def check_presence(correct_port, interval=.25):
|
||||||
return True
|
global ser
|
||||||
|
global justreconnected
|
||||||
|
global serialconnected
|
||||||
|
global justChecked
|
||||||
|
global reading
|
||||||
|
|
||||||
|
portFound = 0
|
||||||
|
while True:
|
||||||
|
|
||||||
|
if (reading == 0):
|
||||||
|
|
||||||
|
|
||||||
|
portFound = 0
|
||||||
|
|
||||||
|
|
||||||
|
for port in serial.tools.list_ports.comports():
|
||||||
|
|
||||||
|
if portName in port.device:
|
||||||
|
|
||||||
|
portFound = 1
|
||||||
|
|
||||||
|
#print (portFound)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
if portFound >= 1:
|
||||||
|
try:
|
||||||
|
ser = serial.Serial(portName, 115200, timeout= None)
|
||||||
|
justChecked = 1
|
||||||
|
serialconnected = 1
|
||||||
|
time.sleep(0.05)
|
||||||
|
justChecked = 0
|
||||||
|
except:
|
||||||
|
continue
|
||||||
|
|
||||||
|
|
||||||
|
else:
|
||||||
|
justreconnected = 1
|
||||||
|
justChecked = 0
|
||||||
|
serialconnected = 0
|
||||||
|
|
||||||
|
ser.close()
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
time.sleep(interval)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
import threading
|
||||||
|
port_controller = threading.Thread(target=check_presence, args=(portName, .25,), daemon=True)
|
||||||
|
#port_controller.daemon(True)
|
||||||
|
port_controller.start()
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
def waitForReconnect():
|
||||||
|
global ser
|
||||||
|
global justChecked
|
||||||
|
global serialconnected
|
||||||
|
serialconnected = 0
|
||||||
|
|
||||||
|
portNotFound = 1
|
||||||
|
|
||||||
|
|
||||||
|
while (portNotFound == 1):
|
||||||
|
portFound = 0
|
||||||
|
|
||||||
|
for port in serial.tools.list_ports.comports():
|
||||||
|
|
||||||
|
if portName in port.device:
|
||||||
|
|
||||||
|
portFound = 1
|
||||||
|
#print (port.device)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
if portFound >= 1:
|
||||||
|
ser = serial.Serial(portName, 115200, timeout= None)
|
||||||
|
justChecked = 1
|
||||||
|
serialconnected = 1
|
||||||
|
time.sleep(0.05)
|
||||||
|
justChecked = 0
|
||||||
|
portNotFound = 0
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
else:
|
||||||
|
justreconnected = 1
|
||||||
|
justChecked = 0
|
||||||
|
serialconnected = 0
|
||||||
|
|
||||||
|
ser.close()
|
||||||
|
portNotFound = 1
|
||||||
|
time.sleep(.05)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
#https://wokwi.com/projects/369024970682423297
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
ser = serial.Serial(portName, 460800, timeout=0.050)
|
|
||||||
|
|
||||||
#the website URL
|
#the website URL
|
||||||
#url_link = "https://wokwi.com/projects/367384677537829889"
|
url_link = "https://wokwi.com/projects/369024970682423297"
|
||||||
|
#url_link = input('\n\n\rPaste the link to you Wokwi project here:\n\n\r')
|
||||||
|
|
||||||
|
|
||||||
|
while True:
|
||||||
|
|
||||||
|
checkurl = ' '
|
||||||
|
|
||||||
|
try:
|
||||||
|
checkurl = requests.get(url_link)
|
||||||
|
if (checkurl.status_code == requests.codes.ok):
|
||||||
|
break
|
||||||
|
else:
|
||||||
|
url_link = input('\n\n\rBad link\n\n\rPaste the link to you Wokwi project here:\n\n\r')
|
||||||
|
continue
|
||||||
|
except:
|
||||||
|
url_link = input('\n\n\rBad link\n\n\rPaste the link to you Wokwi project here:\n\n\r')
|
||||||
|
|
||||||
|
|
||||||
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")
|
print("\n\n\rSave your Wokwi project to update the Jumperless\n\n\r")
|
||||||
|
|
||||||
|
|
||||||
stringified = 0
|
|
||||||
lastDiagram = 1
|
|
||||||
|
def serialTermIn():
|
||||||
|
global serialconnected
|
||||||
|
global ser
|
||||||
|
global justChecked
|
||||||
|
global reading
|
||||||
|
readLength = 0
|
||||||
|
|
||||||
|
while True:
|
||||||
|
try:
|
||||||
|
if (ser.in_waiting > 0):
|
||||||
|
#justChecked = 0
|
||||||
|
reading = 1
|
||||||
|
inputBuffer = b' '
|
||||||
|
|
||||||
|
|
||||||
|
waiting = ser.in_waiting
|
||||||
|
|
||||||
|
while True:
|
||||||
|
inByte = ser.read()
|
||||||
|
|
||||||
|
inputBuffer += inByte
|
||||||
|
|
||||||
|
if (ser.in_waiting == 0):
|
||||||
|
time.sleep(0.05)
|
||||||
|
|
||||||
|
if (ser.in_waiting == 0):
|
||||||
|
break
|
||||||
|
else:
|
||||||
|
continue
|
||||||
|
|
||||||
|
inputBuffer = str(inputBuffer)
|
||||||
|
|
||||||
|
|
||||||
|
inputBuffer.encode()
|
||||||
|
decoded_string = codecs.escape_decode(bytes(inputBuffer, "utf-8"))[0].decode("utf-8")
|
||||||
|
|
||||||
|
decoded_string = decoded_string.lstrip("b' ")
|
||||||
|
decoded_string = decoded_string.rstrip("'")
|
||||||
|
|
||||||
|
print (decoded_string, end='')
|
||||||
|
#print ("!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!")
|
||||||
|
readlength = 0
|
||||||
|
#justChecked = 0
|
||||||
|
reading = 0
|
||||||
|
|
||||||
|
|
||||||
|
except:
|
||||||
|
portNotFound = 1
|
||||||
|
print("!!!!!!")
|
||||||
|
while (portNotFound == 1):
|
||||||
|
portFound = 0
|
||||||
|
|
||||||
|
for port in serial.tools.list_ports.comports():
|
||||||
|
|
||||||
|
if portName in port.device:
|
||||||
|
|
||||||
|
portFound = 1
|
||||||
|
#print (port.device)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
if portFound >= 1:
|
||||||
|
ser = serial.Serial(portName, 115200, timeout= None)
|
||||||
|
justChecked = 1
|
||||||
|
serialconnected = 1
|
||||||
|
time.sleep(0.05)
|
||||||
|
justChecked = 0
|
||||||
|
portNotFound = 0
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
else:
|
||||||
|
justreconnected = 1
|
||||||
|
justChecked = 0
|
||||||
|
serialconnected = 0
|
||||||
|
|
||||||
|
ser.close()
|
||||||
|
portNotFound = 1
|
||||||
|
time.sleep(.1)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
port_controller = threading.Thread(target=serialTermIn, daemon=True)
|
||||||
|
#port_controller.daemon(True)
|
||||||
|
port_controller.start()
|
||||||
|
|
||||||
|
|
||||||
|
def serialTermOut():
|
||||||
|
global serialconnected
|
||||||
|
global ser
|
||||||
|
global justChecked
|
||||||
|
global justreconnected
|
||||||
|
|
||||||
|
resetEntered = 0
|
||||||
|
while True:
|
||||||
|
|
||||||
|
outputBuffer = input()
|
||||||
|
|
||||||
|
if outputBuffer == b'r':
|
||||||
|
resetEntered = 1
|
||||||
|
|
||||||
|
if (serialconnected == 1):
|
||||||
|
#justChecked = 0
|
||||||
|
while (justChecked == 0):
|
||||||
|
time.sleep(0.0001)
|
||||||
|
else:
|
||||||
|
|
||||||
|
#print (outputBuffer)
|
||||||
|
if (outputBuffer != " "):
|
||||||
|
try:
|
||||||
|
#print (outputBuffer.encode('ascii'))
|
||||||
|
ser.write(outputBuffer.encode('ascii'))
|
||||||
|
except:
|
||||||
|
portNotFound = 1
|
||||||
|
|
||||||
|
|
||||||
|
while (portNotFound == 1):
|
||||||
|
portFound = 0
|
||||||
|
|
||||||
|
for port in serial.tools.list_ports.comports():
|
||||||
|
|
||||||
|
if portName in port.device:
|
||||||
|
|
||||||
|
portFound = 1
|
||||||
|
#print (port.device)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
if portFound >= 1:
|
||||||
|
ser = serial.Serial(portName, 115200, timeout= None)
|
||||||
|
justChecked = 1
|
||||||
|
serialconnected = 1
|
||||||
|
time.sleep(0.05)
|
||||||
|
justChecked = 0
|
||||||
|
portNotFound = 0
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
else:
|
||||||
|
justreconnected = 1
|
||||||
|
justChecked = 0
|
||||||
|
serialconnected = 0
|
||||||
|
|
||||||
|
ser.close()
|
||||||
|
portNotFound = 1
|
||||||
|
time.sleep(.1)
|
||||||
|
print (outputBuffer.encode('ascii'))
|
||||||
|
ser.write(outputBuffer.encode('ascii'))
|
||||||
|
|
||||||
|
|
||||||
|
if (resetEntered == 1):
|
||||||
|
time.sleep(.5)
|
||||||
|
print ("reset")
|
||||||
|
justreconnected = 1
|
||||||
|
|
||||||
|
|
||||||
|
#time.sleep(.5)
|
||||||
|
|
||||||
|
port_controller = threading.Thread(target=serialTermOut, daemon=True)
|
||||||
|
|
||||||
|
port_controller.start()
|
||||||
|
|
||||||
|
time.sleep(.75)
|
||||||
|
|
||||||
while True:
|
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)
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
c = d['props']['pageProps']['p']['files'][0]['content']
|
#while portIsUsable(portName) == True:
|
||||||
|
# print('fuck')
|
||||||
l = d['props']['pageProps']['p']['files'][2]['content']
|
# ser.close()
|
||||||
|
# time.sleep(.5)
|
||||||
d = d['props']['pageProps']['p']['files'][1]['content']
|
#ser = serial.Serial(portName, 460800, timeout=0.050)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
f = json.loads(d)
|
|
||||||
|
|
||||||
# cf = json.loads(c)
|
|
||||||
|
|
||||||
|
|
||||||
diagram = str(d)
|
|
||||||
sketch = str(c)
|
|
||||||
libraries = str(l)
|
|
||||||
|
|
||||||
if debug == True:
|
|
||||||
print("\n\n\rdiagram.json\n\r")
|
|
||||||
print(diagram)
|
|
||||||
|
|
||||||
print("\n\n\rsketch.ino\n\r")
|
while (justreconnected == 1):
|
||||||
print(sketch)
|
time.sleep(.001)
|
||||||
|
if serialconnected == 1:
|
||||||
print("\n\n\rlibraries.txt\n\r")
|
break
|
||||||
print(libraries)
|
|
||||||
|
|
||||||
if lastDiagram != diagram:
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
length = len(f["connections"])
|
|
||||||
|
|
||||||
|
|
||||||
p = "{\n"
|
|
||||||
|
|
||||||
|
|
||||||
for i in range(length):
|
|
||||||
|
|
||||||
conn1 = str(f["connections"][i][0])
|
if (serialconnected == 1):
|
||||||
|
|
||||||
if conn1.startswith('pot1:SIG'):
|
result = requests.get(url_link).text
|
||||||
conn1 = "106"
|
doc = BeautifulSoup(result, "html.parser")
|
||||||
elif conn1.startswith('pot2:SIG'):
|
|
||||||
conn1 = "107"
|
|
||||||
|
|
||||||
|
|
||||||
|
s = doc.find('script', type='application/json').get_text()
|
||||||
|
|
||||||
|
stringex = str(s)
|
||||||
|
|
||||||
|
d = json.loads(stringex)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
c = d['props']['pageProps']['p']['files'][0]['content']
|
||||||
|
|
||||||
|
l = d['props']['pageProps']['p']['files'][2]['content']
|
||||||
|
|
||||||
|
d = d['props']['pageProps']['p']['files'][1]['content']
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
f = json.loads(d)
|
||||||
|
|
||||||
|
# cf = json.loads(c)
|
||||||
|
|
||||||
|
|
||||||
|
diagram = str(d)
|
||||||
|
sketch = str(c)
|
||||||
|
libraries = str(l)
|
||||||
|
|
||||||
|
if debug == True:
|
||||||
|
print("\n\n\rdiagram.json\n\r")
|
||||||
|
print(diagram)
|
||||||
|
|
||||||
if conn1.startswith("bb1:") == True:
|
print("\n\n\rsketch.ino\n\r")
|
||||||
periodIndex = conn1.find('.')
|
print(sketch)
|
||||||
conn1 = conn1[4:periodIndex]
|
|
||||||
|
print("\n\n\rlibraries.txt\n\r")
|
||||||
|
print(libraries)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
if (justreconnected == 1):
|
||||||
|
print ('Reconnected')
|
||||||
|
|
||||||
|
lastDiagram = '-1'
|
||||||
|
#print (lastDiagram)
|
||||||
|
#time.sleep(1.8)
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
if (lastDiagram != diagram):
|
||||||
|
|
||||||
|
justreconnected = 0
|
||||||
|
length = len(f["connections"])
|
||||||
|
|
||||||
|
|
||||||
|
p = "{\n"
|
||||||
|
|
||||||
|
|
||||||
|
for i in range(length):
|
||||||
|
|
||||||
if conn1.endswith('t') == True:
|
conn1 = str(f["connections"][i][0])
|
||||||
conn1 = conn1[0:(len(conn1)-1)]
|
|
||||||
elif conn1.endswith('b') == True:
|
if conn1.startswith('pot1:SIG'):
|
||||||
conn1 = conn1[0:(len(conn1)-1)]
|
conn1 = "106"
|
||||||
conn1 = int(conn1)
|
elif conn1.startswith('pot2:SIG'):
|
||||||
conn1 = conn1 + 30
|
conn1 = "107"
|
||||||
conn1 = str(conn1)
|
|
||||||
elif conn1.endswith('n') == True:
|
|
||||||
conn1 = "100"
|
if conn1.startswith("bb1:") == True:
|
||||||
elif conn1.startswith("GND") == True:
|
periodIndex = conn1.find('.')
|
||||||
conn1 = "100"
|
conn1 = conn1[4:periodIndex]
|
||||||
elif conn1.endswith('p') == True:
|
|
||||||
if conn1.startswith('t') == True:
|
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"
|
conn1 = "105"
|
||||||
elif conn1.startswith('b') == True:
|
elif conn1 == "3.3V":
|
||||||
conn1 = "103"
|
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)
|
||||||
|
|
||||||
|
|
||||||
if conn1.startswith("nano:") == True:
|
conn2 = str(f["connections"][i][1])
|
||||||
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"
|
|
||||||
|
|
||||||
|
if conn2.startswith('pot1:SIG'):
|
||||||
|
conn2 = "106"
|
||||||
|
elif conn2.startswith('pot2:SIG'):
|
||||||
|
conn2 = "107"
|
||||||
|
|
||||||
|
|
||||||
|
if conn2.startswith("bb1:") == True:
|
||||||
|
periodIndex = conn2.find('.')
|
||||||
|
conn2 = conn2[4:periodIndex]
|
||||||
|
|
||||||
elif conn1.startswith("A") == True:
|
if conn2.endswith('t') == True:
|
||||||
conn1 = conn1[1:(len(conn1))]
|
conn2 = conn2[0:(len(conn2)-1)]
|
||||||
conn1 = int(conn1)
|
elif conn2.endswith('b') == True:
|
||||||
conn1 = conn1 + 86
|
conn2 = conn2[0:(len(conn2)-1)]
|
||||||
conn1 = str(conn1)
|
conn2 = int(conn2)
|
||||||
elif conn1.isdigit() == True:
|
conn2 = conn2 + 30
|
||||||
conn1 = int(conn1)
|
conn2 = str(conn2)
|
||||||
conn1 = conn1 + 70
|
elif conn2.endswith('n') == True:
|
||||||
conn1 = str(conn1)
|
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:
|
||||||
conn2 = str(f["connections"][i][1])
|
periodIndex = conn2.find('.')
|
||||||
|
conn2 = conn2[5:len(conn2)]
|
||||||
if conn2.startswith('pot1:SIG'):
|
|
||||||
conn2 = "106"
|
if conn2.startswith("GND") == True:
|
||||||
elif conn2.startswith('pot2:SIG'):
|
conn2 = "100"
|
||||||
conn2 = "107"
|
elif conn2 == "AREF":
|
||||||
|
conn2 = "85"
|
||||||
|
elif conn2 == "RESET":
|
||||||
if conn2.startswith("bb1:") == True:
|
conn2 = "84"
|
||||||
periodIndex = conn2.find('.')
|
elif conn2 == "5V":
|
||||||
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"
|
conn2 = "105"
|
||||||
elif conn2.startswith('b') == True:
|
elif conn2 == "3.3V":
|
||||||
conn2 = "103"
|
conn2 = "103"
|
||||||
|
elif conn2 == "5V":
|
||||||
|
conn2 = "105"
|
||||||
|
|
||||||
|
elif conn2.startswith("A") == True and conn2 != "AREF":
|
||||||
if conn2.startswith("nano:") == True:
|
|
||||||
periodIndex = conn2.find('.')
|
conn2 = conn2[1:(len(conn2))]
|
||||||
conn2 = conn2[5:len(conn2)]
|
conn2 = int(conn2)
|
||||||
|
conn2 = conn2 + 86
|
||||||
if conn2.startswith("GND") == True:
|
conn2 = str(conn2)
|
||||||
conn2 = "100"
|
elif conn2.isdigit() == True:
|
||||||
elif conn2 == "AREF":
|
conn2 = int(conn2)
|
||||||
conn2 = "85"
|
conn2 = conn2 + 70
|
||||||
elif conn2 == "RESET":
|
conn2 = str(conn2)
|
||||||
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))]
|
if conn1.isdigit()== True and conn2.isdigit() == True:
|
||||||
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 + conn1 + '-')
|
||||||
p = (p + conn2 + ',\n')
|
p = (p + conn2 + ',\n')
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
p = (p + "}\n{\n}")
|
||||||
|
|
||||||
|
lastDiagram = diagram
|
||||||
|
|
||||||
|
try:
|
||||||
|
ser.write('f'.encode())
|
||||||
|
|
||||||
p = (p + "}\n{\n}")
|
time.sleep(0.05)
|
||||||
|
|
||||||
lastDiagram = diagram
|
ser.write(p.encode())
|
||||||
|
|
||||||
|
except:
|
||||||
ser.write('f'.encode())
|
#continue
|
||||||
|
waitForReconnect()
|
||||||
time.sleep(0.1)
|
|
||||||
|
ser.write('f'.encode())
|
||||||
ser.write(p.encode())
|
|
||||||
|
time.sleep(0.05)
|
||||||
#print (p)
|
|
||||||
|
ser.write(p.encode())
|
||||||
else:
|
|
||||||
time.sleep(.5)
|
#print (p)
|
||||||
|
|
||||||
|
else:
|
||||||
|
time.sleep(.5)
|
||||||
|
|
||||||
|
|
||||||
|
@ -13,8 +13,8 @@ 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.usbmodem11101
|
upload_port = /dev/cu.usbmodem11301
|
||||||
monitor_port = /dev/cu.usbmodem11101
|
monitor_port = /dev/cu.usbmodem11301
|
||||||
extra_scripts = post:scripts/extra_script.py
|
extra_scripts = post:scripts/extra_script.py
|
||||||
monitor_speed = 256000
|
monitor_speed = 256000
|
||||||
|
|
||||||
|
@ -870,7 +870,10 @@ void debugFlagSet(int flag)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
delay(2);
|
||||||
EEPROM.commit();
|
EEPROM.commit();
|
||||||
|
delay(5);
|
||||||
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
void runCommandAfterReset(char command)
|
void runCommandAfterReset(char command)
|
||||||
|
@ -13,6 +13,7 @@ rgbColor netColors[MAX_NETS] = {0};
|
|||||||
uint8_t saturation = 254;
|
uint8_t saturation = 254;
|
||||||
uint8_t brightness = BRIGHTNESS;
|
uint8_t brightness = BRIGHTNESS;
|
||||||
|
|
||||||
|
int showLEDsCore2 = 0;
|
||||||
|
|
||||||
|
|
||||||
#ifdef EEPROMSTUFF
|
#ifdef EEPROMSTUFF
|
||||||
@ -29,8 +30,8 @@ uint8_t brightness = BRIGHTNESS;
|
|||||||
{0x00, 0xFF, 0x30},
|
{0x00, 0xFF, 0x30},
|
||||||
{0xFF, 0x41, 0x14},
|
{0xFF, 0x41, 0x14},
|
||||||
{0xFF, 0x10, 0x40},
|
{0xFF, 0x10, 0x40},
|
||||||
{0xFF, 0x78, 0xaa},
|
{0xeF, 0x78, 0x7a},
|
||||||
{0xFF, 0x40, 0x78},
|
{0xeF, 0x40, 0x7f},
|
||||||
{0xFF, 0xff, 0xff},
|
{0xFF, 0xff, 0xff},
|
||||||
{0xff, 0xFF, 0xff}};
|
{0xff, 0xFF, 0xff}};
|
||||||
|
|
||||||
@ -45,7 +46,7 @@ void initLEDs(void)
|
|||||||
{
|
{
|
||||||
pinMode(LED_PIN, OUTPUT);
|
pinMode(LED_PIN, OUTPUT);
|
||||||
leds.begin(); // INITIALIZE NeoPixel strip object (REQUIRED)
|
leds.begin(); // INITIALIZE NeoPixel strip object (REQUIRED)
|
||||||
leds.show(); // Turn OFF all pixels ASAP
|
showLEDsCore2 = 1; // Turn OFF all pixels ASAP
|
||||||
leds.setBrightness(BRIGHTNESS);
|
leds.setBrightness(BRIGHTNESS);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -58,7 +59,7 @@ void colorWipe(uint32_t color, int wait)
|
|||||||
{ // For each pixel in strip...
|
{ // For each pixel in strip...
|
||||||
|
|
||||||
leds.setPixelColor(i, color); // Set pixel's color (in RAM)
|
leds.setPixelColor(i, color); // Set pixel's color (in RAM)
|
||||||
leds.show(); // Update strip to match
|
showLEDsCore2 = 1; // Update strip to match
|
||||||
delay(wait); // Pause for a moment
|
delay(wait); // Pause for a moment
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -76,7 +77,7 @@ void rainbowy(int saturation, int brightness, int wait)
|
|||||||
leds.rainbow(firstPixelHue, 1, saturation, brightness, true);
|
leds.rainbow(firstPixelHue, 1, saturation, brightness, true);
|
||||||
// Above line is equivalent to:
|
// Above line is equivalent to:
|
||||||
// strip.rainbow(firstPixelHue, 1, 255, 255, true);
|
// strip.rainbow(firstPixelHue, 1, 255, 255, true);
|
||||||
leds.show(); // Update strip with new contents
|
showLEDsCore2 = 1;// Update strip with new contents
|
||||||
delay(wait); // Pause for a moment
|
delay(wait); // Pause for a moment
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -89,7 +90,7 @@ void clearLEDs(void)
|
|||||||
leds.setPixelColor(i, 0); // Set pixel's color (in RAM)
|
leds.setPixelColor(i, 0); // Set pixel's color (in RAM)
|
||||||
// Update strip to match
|
// Update strip to match
|
||||||
}
|
}
|
||||||
leds.show();
|
showLEDsCore2 = 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
void assignNetColors(void)
|
void assignNetColors(void)
|
||||||
@ -162,7 +163,7 @@ if (debugLEDs)
|
|||||||
leds.setPixelColor(railsToPixelMap[3][i], railColors[3]); // bottom negative rail
|
leds.setPixelColor(railsToPixelMap[3][i], railColors[3]); // bottom negative rail
|
||||||
*/
|
*/
|
||||||
}
|
}
|
||||||
leds.show();
|
showLEDsCore2 = 1;
|
||||||
|
|
||||||
|
|
||||||
int skipSpecialColors = 0;
|
int skipSpecialColors = 0;
|
||||||
@ -270,7 +271,7 @@ uint32_t packRgb(uint8_t r, uint8_t g, uint8_t b)
|
|||||||
|
|
||||||
|
|
||||||
|
|
||||||
void lightUpNet(int netNumber, int node, int onOff , int brightness2)
|
void lightUpNet(int netNumber, int node, int onOff , int brightness2, int hueShift)
|
||||||
{
|
{
|
||||||
|
|
||||||
if (net[netNumber].nodes[1] != 0 && net[netNumber].nodes[1] < 62)
|
if (net[netNumber].nodes[1] != 0 && net[netNumber].nodes[1] < 62)
|
||||||
@ -289,8 +290,20 @@ void lightUpNet(int netNumber, int node, int onOff , int brightness2)
|
|||||||
if (onOff == 1)
|
if (onOff == 1)
|
||||||
{
|
{
|
||||||
|
|
||||||
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);
|
|
||||||
|
uint32_t color;
|
||||||
|
|
||||||
|
|
||||||
|
if (hueShift != 0)
|
||||||
|
{
|
||||||
|
struct rgbColor colorToShift = {net[netNumber].color.r, net[netNumber].color.g, net[netNumber].color.b};
|
||||||
|
struct rgbColor shiftedColor = shiftHue(colorToShift, hueShift);
|
||||||
|
color = packRgb((shiftedColor.r * brightness2) >> 8, (shiftedColor.g * brightness2) >> 8, (shiftedColor.b * brightness2) >> 8);
|
||||||
|
} else {
|
||||||
|
color = packRgb((net[netNumber].color.r * brightness2) >> 8, (net[netNumber].color.g * brightness2) >> 8, (net[netNumber].color.b * brightness2) >> 8);
|
||||||
|
}
|
||||||
|
|
||||||
leds.setPixelColor(nodesToPixelMap[net[netNumber].nodes[j]], color);
|
leds.setPixelColor(nodesToPixelMap[net[netNumber].nodes[j]], color);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
@ -301,9 +314,37 @@ void lightUpNet(int netNumber, int node, int onOff , int brightness2)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
leds.show();
|
showLEDsCore2 = 1;
|
||||||
delay(1);
|
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
struct rgbColor shiftHue (struct rgbColor colorToShift, int hueShift)
|
||||||
|
|
||||||
|
{
|
||||||
|
|
||||||
|
|
||||||
|
struct hsvColor colorToShiftHsv = RgbToHsv(colorToShift);
|
||||||
|
|
||||||
|
|
||||||
|
colorToShiftHsv.h = colorToShiftHsv.h + hueShift;
|
||||||
|
|
||||||
|
if (colorToShiftHsv.h > 255)
|
||||||
|
{
|
||||||
|
colorToShiftHsv.h = colorToShiftHsv.h - 255;
|
||||||
|
}
|
||||||
|
|
||||||
|
struct rgbColor colorToShiftRgb = HsvToRgb(colorToShiftHsv);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
return colorToShiftRgb;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -341,7 +382,7 @@ for (int j = 0; j < 4; j++)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
leds.show();
|
showLEDsCore2 = 1;
|
||||||
delay(1);
|
delay(1);
|
||||||
|
|
||||||
}
|
}
|
||||||
@ -357,7 +398,7 @@ void showNets(void)
|
|||||||
leds.setPixelColor(bbPixelToNodesMap[net[i].nodes[j]], color);
|
leds.setPixelColor(bbPixelToNodesMap[net[i].nodes[j]], color);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
leds.show();
|
showLEDsCore2 = 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
rgbColor HsvToRgb(hsvColor hsv)
|
rgbColor HsvToRgb(hsvColor hsv)
|
||||||
|
@ -12,6 +12,10 @@
|
|||||||
|
|
||||||
extern Adafruit_NeoPixel leds;
|
extern Adafruit_NeoPixel leds;
|
||||||
extern bool debugLEDs;
|
extern bool debugLEDs;
|
||||||
|
|
||||||
|
extern int showLEDsCore2;
|
||||||
|
|
||||||
|
|
||||||
typedef struct rgbColor
|
typedef struct rgbColor
|
||||||
{
|
{
|
||||||
unsigned char r;
|
unsigned char r;
|
||||||
@ -45,7 +49,7 @@ 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];
|
||||||
|
struct rgbColor shiftHue (struct rgbColor colorToShift, int hueShift);
|
||||||
void initLEDs(void);
|
void initLEDs(void);
|
||||||
void clearLEDs(void);
|
void clearLEDs(void);
|
||||||
void colorWipe(uint32_t color, int wait);
|
void colorWipe(uint32_t color, int wait);
|
||||||
@ -54,7 +58,7 @@ void showNets(void);
|
|||||||
void assignNetColors (void);
|
void assignNetColors (void);
|
||||||
void lightUpRail (int railNumber, int onOff = 1, int brightness = BRIGHTNESS);
|
void lightUpRail (int railNumber, int onOff = 1, int brightness = BRIGHTNESS);
|
||||||
|
|
||||||
void lightUpNet (int netNumber = -1 , 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, int hueShift = 0);//-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);
|
||||||
|
@ -625,7 +625,7 @@ 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\tColor\t\tDo Not Intersects");
|
Serial.print("\n\rIndex\tName\t\tNumber\t\tNodes\t\t\tBridges");
|
||||||
|
|
||||||
int tabs = 0;
|
int tabs = 0;
|
||||||
for (int i = 8; i < MAX_NETS; i++)
|
for (int i = 8; i < MAX_NETS; i++)
|
||||||
|
@ -20,8 +20,6 @@
|
|||||||
|
|
||||||
#define DAC_RESOLUTION 9
|
#define DAC_RESOLUTION 9
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
float 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};
|
||||||
@ -33,11 +31,13 @@ uint32_t halvePeriod[3] = {0, 0, 0};
|
|||||||
// r = random
|
// r = random
|
||||||
char mode[3] = {'z', 'z', 'z'};
|
char mode[3] = {'z', 'z', 'z'};
|
||||||
|
|
||||||
|
int dacOn[3] = {0, 0, 0};
|
||||||
|
int amplitude[3] = {4095, 4040, 0};
|
||||||
|
int offset[3] = {2047, 1932, 2047};
|
||||||
|
int calib[3] = {-10, 100, 0};
|
||||||
|
|
||||||
MCP4725_PICO dac0_5V(5.0);
|
MCP4725_PICO dac0_5V(5.0);
|
||||||
MCP4725_PICO dac1_8V(8.0);
|
MCP4725_PICO dac1_8V(15.0);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
INA219 INA0(0x40);
|
INA219 INA0(0x40);
|
||||||
INA219 INA1(0x41);
|
INA219 INA1(0x41);
|
||||||
@ -49,91 +49,65 @@ uint32_t lastTime = 0;
|
|||||||
uint16_t sine0[360];
|
uint16_t sine0[360];
|
||||||
uint16_t sine1[360];
|
uint16_t sine1[360];
|
||||||
|
|
||||||
//ADCInput adc(A3);
|
// ADCInput adc(A3);
|
||||||
|
|
||||||
|
|
||||||
void initADC(void)
|
void initADC(void)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
|
||||||
/// adc.setBuffers(1,64);
|
pinMode(ADC0_PIN, INPUT);
|
||||||
// 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(ADC1_PIN, INPUT);
|
||||||
pinMode(ADC2_PIN, INPUT);
|
pinMode(ADC2_PIN, INPUT);
|
||||||
pinMode(ADC3_PIN, INPUT);
|
pinMode(ADC3_PIN, INPUT);
|
||||||
|
|
||||||
gpio_set_function(ADC3_PIN, GPIO_FUNC_NULL);
|
gpio_set_function(ADC3_PIN, GPIO_FUNC_NULL);
|
||||||
adc_gpio_init(ADC3_PIN);
|
adc_gpio_init(ADC3_PIN);
|
||||||
adc_select_input(3);
|
adc_select_input(3);
|
||||||
|
|
||||||
adc_fifo_setup(true, false, 0, false, false);
|
|
||||||
adc_run(true);
|
|
||||||
analogReadResolution(12);
|
|
||||||
|
|
||||||
|
|
||||||
|
adc_fifo_setup(true, false, 0, false, false);
|
||||||
|
adc_run(true);
|
||||||
|
analogReadResolution(12);
|
||||||
}
|
}
|
||||||
|
|
||||||
void initDAC(void)
|
void initDAC(void)
|
||||||
{
|
{
|
||||||
//Wire.begin();
|
// Wire.begin();
|
||||||
dac1_8V.begin(MCP4725A1_Addr_A01, i2c0, 3000, 4,5);
|
dac1_8V.begin(MCP4725A1_Addr_A01, i2c0, 3000, 4, 5);
|
||||||
dac0_5V.begin(MCP4725A0_Addr_A00, i2c0, 3000, 4,5);
|
dac0_5V.begin(MCP4725A0_Addr_A00, i2c0, 3000, 4, 5);
|
||||||
|
|
||||||
//
|
//
|
||||||
|
delay(1);
|
||||||
dac0_5V.setVoltage(4.0);
|
dac0_5V.setVoltage(0.00,MCP4725_EEPROM_Mode,MCP4725_PowerDown_Off);
|
||||||
dac1_8V.setVoltage(1.0);
|
delay(1);
|
||||||
|
dac0_5V.setVoltage(0.00);
|
||||||
|
//dac0_5V.setInputCode(0,MCP4725_EEPROM_Mode,MCP4725_PowerDown_Off);
|
||||||
|
delay(1);
|
||||||
|
dac1_8V.setInputCode(offset[1] + calib[1],MCP4725_EEPROM_Mode,MCP4725_PowerDown_Off);
|
||||||
|
delay(1);
|
||||||
|
dac1_8V.setInputCode(offset[1] + calib[1]);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void initINA219(void)
|
void initINA219(void)
|
||||||
{
|
{
|
||||||
|
|
||||||
// delay(3000);
|
// delay(3000);
|
||||||
Serial.println(__FILE__);
|
//Serial.println(__FILE__);
|
||||||
Serial.print("INA219_LIB_VERSION: ");
|
//Serial.print("INA219_LIB_VERSION: ");
|
||||||
Serial.println(INA219_LIB_VERSION);
|
//Serial.println(INA219_LIB_VERSION);
|
||||||
|
|
||||||
|
//Wire.begin();
|
||||||
|
//Wire.setClock(1000000);
|
||||||
Wire.begin();
|
Wire.begin();
|
||||||
|
|
||||||
if (!INA0.begin() || !INA1.begin())
|
if (!INA0.begin() || !INA1.begin())
|
||||||
{
|
{
|
||||||
Serial.println("Failed to find INA219 chip");
|
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);
|
INA0.setMaxCurrentShunt(1, 2);
|
||||||
INA1.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(INA0.setBusVoltageRange(16));
|
||||||
Serial.println(INA1.setBusVoltageRange(16));
|
Serial.println(INA1.setBusVoltageRange(16));
|
||||||
@ -179,61 +153,24 @@ void dacSine(int resolution)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void setDac0_5V(float voltage)
|
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.setVoltage(voltage);
|
dac0_5V.setVoltage(voltage);
|
||||||
|
|
||||||
// if (dac1_8V.setVoltage(value, 100000) == false)
|
|
||||||
//{
|
|
||||||
// Serial.println("dac1_8V.setVoltage() failed");
|
|
||||||
// }
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void setDac1_8V(float voltage)
|
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.setVoltage(voltage);
|
dac1_8V.setVoltage(voltage);
|
||||||
|
|
||||||
// if (dac1_8V.setVoltage(value, 100000) == false)
|
|
||||||
//{
|
|
||||||
// Serial.println("dac1_8V.setVoltage() failed");
|
|
||||||
// }
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void refillTable(int amplitude, int offset, int dac)
|
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++)
|
||||||
@ -255,34 +192,34 @@ void refillTable(int amplitude, int offset, int dac)
|
|||||||
}
|
}
|
||||||
void GetAdc29Status(int i)
|
void GetAdc29Status(int i)
|
||||||
{
|
{
|
||||||
gpio_function gpio29Function = gpio_get_function(29);
|
gpio_function gpio29Function = gpio_get_function(29);
|
||||||
Serial.print("GPIO29 func: ");
|
Serial.print("GPIO29 func: ");
|
||||||
Serial.println(gpio29Function);
|
Serial.println(gpio29Function);
|
||||||
|
|
||||||
bool pd = gpio_is_pulled_down(29);
|
bool pd = gpio_is_pulled_down(29);
|
||||||
Serial.print("GPIO29 pd: ");
|
Serial.print("GPIO29 pd: ");
|
||||||
Serial.println(pd);
|
Serial.println(pd);
|
||||||
|
|
||||||
bool h = gpio_is_input_hysteresis_enabled(29);
|
bool h = gpio_is_input_hysteresis_enabled(29);
|
||||||
Serial.print("GPIO29 h: ");
|
Serial.print("GPIO29 h: ");
|
||||||
Serial.println(h);
|
Serial.println(h);
|
||||||
|
|
||||||
gpio_slew_rate slew = gpio_get_slew_rate(29);
|
gpio_slew_rate slew = gpio_get_slew_rate(29);
|
||||||
Serial.print("GPIO29 slew: ");
|
Serial.print("GPIO29 slew: ");
|
||||||
Serial.println(slew);
|
Serial.println(slew);
|
||||||
|
|
||||||
gpio_drive_strength drive = gpio_get_drive_strength(29);
|
gpio_drive_strength drive = gpio_get_drive_strength(29);
|
||||||
Serial.print("GPIO29 drive: ");
|
Serial.print("GPIO29 drive: ");
|
||||||
Serial.println(drive);
|
Serial.println(drive);
|
||||||
|
|
||||||
int irqmask = gpio_get_irq_event_mask(29);
|
int irqmask = gpio_get_irq_event_mask(29);
|
||||||
Serial.print("GPIO29 irqmask: ");
|
Serial.print("GPIO29 irqmask: ");
|
||||||
Serial.println(irqmask);
|
Serial.println(irqmask);
|
||||||
|
|
||||||
bool out = gpio_is_dir_out(29);
|
bool out = gpio_is_dir_out(29);
|
||||||
Serial.print("GPIO29 out: ");
|
Serial.print("GPIO29 out: ");
|
||||||
Serial.println(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);
|
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)
|
float readAdc(int channel, int samples)
|
||||||
@ -290,35 +227,28 @@ float readAdc(int channel, int samples)
|
|||||||
int adcReadingAverage = 0;
|
int adcReadingAverage = 0;
|
||||||
for (int i = 0; i < 20; i++)
|
for (int i = 0; i < 20; i++)
|
||||||
{
|
{
|
||||||
adcReadingAverage += analogRead(28);
|
adcReadingAverage += analogRead(28);
|
||||||
delay(5);
|
delay(5);
|
||||||
}
|
}
|
||||||
|
|
||||||
int adc3Reading = adcReadingAverage/20;
|
int adc3Reading = adcReadingAverage / 20;
|
||||||
Serial.print(adc3Reading);
|
Serial.print(adc3Reading);
|
||||||
|
|
||||||
float adc3Voltage = (adc3Reading - 2528) / 220.0; //painstakingly measured
|
float adc3Voltage = (adc3Reading - 2528) / 220.0; // painstakingly measured
|
||||||
return adc3Voltage;
|
return adc3Voltage;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void waveGen(void)
|
void waveGen(void)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
|
||||||
listSpecialNets();
|
listSpecialNets();
|
||||||
listNets();
|
listNets();
|
||||||
|
|
||||||
int activeDac = 3;
|
int activeDac = 3;
|
||||||
|
|
||||||
mode[0] = 's';
|
mode[0] = 's';
|
||||||
mode[1] = 's';
|
mode[1] = 's';
|
||||||
mode[2] = 's';
|
mode[2] = 's';
|
||||||
int dacOn[3] = {0, 0, 0};
|
|
||||||
int amplitude[3] = {4095, 4140, 0};
|
|
||||||
int offset[3] = {2047, 1932, 2047};
|
|
||||||
int calib[3] = {-10, 100, 0};
|
|
||||||
|
|
||||||
|
|
||||||
refillTable(amplitude[0], offset[0] + calib[0], 0);
|
refillTable(amplitude[0], offset[0] + calib[0], 0);
|
||||||
@ -338,16 +268,11 @@ void waveGen(void)
|
|||||||
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\tx = exit\t\t \n\r");
|
Serial.println("\th = show this menu\tx = exit\t\t \n\r");
|
||||||
|
|
||||||
|
period[activeDac] = 1e6 / (freq[activeDac] / 10);
|
||||||
|
|
||||||
period[activeDac] = 1e6 / (freq[activeDac]/10);
|
|
||||||
halvePeriod[activeDac] = period[activeDac] / 2;
|
halvePeriod[activeDac] = period[activeDac] / 2;
|
||||||
int chars = 0;
|
int chars = 0;
|
||||||
|
|
||||||
|
chars = 0;
|
||||||
|
|
||||||
|
|
||||||
chars = 0;
|
|
||||||
while (1)
|
while (1)
|
||||||
{
|
{
|
||||||
yield();
|
yield();
|
||||||
@ -355,35 +280,68 @@ void waveGen(void)
|
|||||||
|
|
||||||
count++;
|
count++;
|
||||||
|
|
||||||
|
// float adc3Voltage = (adc3Reading - 2528) / 220.0; //painstakingly measured
|
||||||
|
// float adc0Voltage = ((adc0Reading) / 400.0) - 0.69; //- 0.93; //painstakingly measured
|
||||||
|
|
||||||
|
int adc0Reading = 0;
|
||||||
|
int brightness0 = 0;
|
||||||
|
int hueShift0 = 0;
|
||||||
|
|
||||||
|
|
||||||
|
if (dacOn[0] == 1)
|
||||||
|
{
|
||||||
|
adc0Reading = INA1.getBusVoltage_mV();
|
||||||
|
adc0Reading = abs(adc0Reading );
|
||||||
|
hueShift0 = map(adc0Reading, 0, 5000, -90, 0);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
adc0Reading = amplitude[0];
|
||||||
|
}
|
||||||
|
brightness0 = map(adc0Reading, 0, 5000, 10, 254);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
lightUpNet(4, -1, 1, brightness0, hueShift0);
|
||||||
|
|
||||||
|
|
||||||
|
int adc1Reading = 0;
|
||||||
|
int brightness1 = 0;
|
||||||
|
int hueShift1 = 0;
|
||||||
|
if (dacOn[1] == 1)
|
||||||
|
{
|
||||||
|
adc1Reading = dac1_8V.getInputCode();
|
||||||
|
|
||||||
|
adc1Reading = adc1Reading - 2048;
|
||||||
|
|
||||||
|
hueShift1 = map(adc1Reading, -2048, 2048, -50, 45);
|
||||||
|
|
||||||
|
|
||||||
|
adc1Reading = abs(adc1Reading );
|
||||||
|
|
||||||
|
} else {
|
||||||
|
adc1Reading = amplitude[1];
|
||||||
|
}
|
||||||
|
|
||||||
|
brightness1 = map(adc1Reading, 0, 2050, 10, 254);
|
||||||
|
|
||||||
|
lightUpNet(5, -1, 1, brightness1, hueShift1);
|
||||||
|
|
||||||
//float adc3Voltage = (adc3Reading - 2528) / 220.0; //painstakingly measured
|
|
||||||
//float adc0Voltage = ((adc0Reading) / 400.0) - 0.69; //- 0.93; //painstakingly measured
|
|
||||||
if (now - lastTime > 100000)
|
if (now - lastTime > 100000)
|
||||||
{
|
{
|
||||||
|
|
||||||
//int adc0Reading = analogRead(26);
|
//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);
|
|
||||||
|
|
||||||
|
//Serial.println(adc1Reading);
|
||||||
|
|
||||||
lastTime = now;
|
lastTime = now;
|
||||||
// Serial.println(count); // show # updates per 0.1 second
|
// Serial.println(count); // show # updates per 0.1 second
|
||||||
count = 0;
|
count = 0;
|
||||||
if (Serial.available())
|
|
||||||
|
if (Serial.available() == 0)
|
||||||
|
{
|
||||||
|
// break;
|
||||||
|
}
|
||||||
|
else
|
||||||
{
|
{
|
||||||
int c = Serial.read();
|
int c = Serial.read();
|
||||||
switch (c)
|
switch (c)
|
||||||
@ -392,8 +350,10 @@ chars += Serial.print(adc0Reading);
|
|||||||
if (freq[activeDac] >= 1.0)
|
if (freq[activeDac] >= 1.0)
|
||||||
{
|
{
|
||||||
|
|
||||||
freq[activeDac]++;
|
freq[activeDac]++;
|
||||||
} else {
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
freq[activeDac] += 0.1;
|
freq[activeDac] += 0.1;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
@ -401,10 +361,14 @@ chars += Serial.print(adc0Reading);
|
|||||||
|
|
||||||
if (freq[activeDac] > 1.0)
|
if (freq[activeDac] > 1.0)
|
||||||
{
|
{
|
||||||
freq[activeDac]--;
|
freq[activeDac]--;
|
||||||
} else if (freq[activeDac] > 0.1){
|
}
|
||||||
|
else if (freq[activeDac] > 0.1)
|
||||||
|
{
|
||||||
freq[activeDac] -= 0.1;
|
freq[activeDac] -= 0.1;
|
||||||
} else {
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
freq[activeDac] = 0.0;
|
freq[activeDac] = 0.0;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -418,7 +382,8 @@ chars += Serial.print(adc0Reading);
|
|||||||
case '8':
|
case '8':
|
||||||
if (activeDac == 0)
|
if (activeDac == 0)
|
||||||
{
|
{
|
||||||
dac0_5V.setVoltage(0);
|
dac0_5V.setVoltage(0.0);
|
||||||
|
dacOn[0] = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (activeDac != 3)
|
if (activeDac != 3)
|
||||||
@ -426,16 +391,18 @@ chars += Serial.print(adc0Reading);
|
|||||||
|
|
||||||
activeDac = 1;
|
activeDac = 1;
|
||||||
|
|
||||||
if (dacOn[activeDac] == 0)
|
if (dacOn[1] == 0)
|
||||||
{
|
{
|
||||||
dac1_8V.setInputCode(amplitude[activeDac]);
|
dac1_8V.setInputCode(offset[1] + calib[1]);
|
||||||
}
|
}
|
||||||
|
|
||||||
break;
|
break;
|
||||||
case '5':
|
case '5':
|
||||||
if (activeDac == 1)
|
if (activeDac == 1)
|
||||||
{
|
{
|
||||||
dac1_8V.setInputCode(amplitude[activeDac]);
|
dac1_8V.setInputCode(offset[1] + calib[1]);
|
||||||
|
dacOn[1] = 0;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (activeDac != 3)
|
if (activeDac != 3)
|
||||||
@ -444,11 +411,11 @@ chars += Serial.print(adc0Reading);
|
|||||||
activeDac = 0;
|
activeDac = 0;
|
||||||
if (dacOn[activeDac] == 0)
|
if (dacOn[activeDac] == 0)
|
||||||
{
|
{
|
||||||
dac0_5V.setVoltage(0);
|
dac0_5V.setVoltage(0.0);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 'c':
|
case 'c':
|
||||||
//freq[activeDac] = 0;
|
// freq[activeDac] = 0;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 's':
|
case 's':
|
||||||
@ -486,8 +453,26 @@ chars += Serial.print(adc0Reading);
|
|||||||
mode[activeDac] = c;
|
mode[activeDac] = c;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 'x':
|
case 'x':
|
||||||
|
case 'f':
|
||||||
|
case '{':
|
||||||
|
{
|
||||||
|
if (mode[0] != 'v')
|
||||||
|
{
|
||||||
|
dac0_5V.setVoltage(0.0);
|
||||||
|
|
||||||
|
}
|
||||||
|
if (mode[1] != 'v')
|
||||||
|
{
|
||||||
|
|
||||||
|
dac1_8V.setInputCode(offset[1]);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
return;
|
return;
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -525,14 +510,15 @@ chars += Serial.print(adc0Reading);
|
|||||||
Serial.print("freq: ");
|
Serial.print("freq: ");
|
||||||
Serial.print(freq[activeDac]);
|
Serial.print(freq[activeDac]);
|
||||||
// Serial.print("\t\n\r");
|
// Serial.print("\t\n\r");
|
||||||
} Serial.print("\tdacon");
|
}
|
||||||
|
/*
|
||||||
|
Serial.print("\tdacon");
|
||||||
for (int i = 0; i < 3; i++)
|
for (int i = 0; i < 3; i++)
|
||||||
{
|
{
|
||||||
Serial.print("\t");
|
Serial.print("\t");
|
||||||
|
|
||||||
Serial.print(dacOn[i]);
|
|
||||||
|
|
||||||
}
|
Serial.print(dacOn[i]);
|
||||||
|
}*/
|
||||||
Serial.println();
|
Serial.println();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -553,7 +539,7 @@ chars += Serial.print(adc0Reading);
|
|||||||
else
|
else
|
||||||
{
|
{
|
||||||
if (activeDac == 0 && dacOn[activeDac] == 1)
|
if (activeDac == 0 && dacOn[activeDac] == 1)
|
||||||
dac0_5V.setInputCode(offset[activeDac]);
|
dac0_5V.setInputCode(0);
|
||||||
else if (activeDac == 1 && dacOn[activeDac] == 1)
|
else if (activeDac == 1 && dacOn[activeDac] == 1)
|
||||||
dac1_8V.setInputCode(offset[activeDac]);
|
dac1_8V.setInputCode(offset[activeDac]);
|
||||||
}
|
}
|
||||||
@ -569,9 +555,9 @@ chars += Serial.print(adc0Reading);
|
|||||||
{
|
{
|
||||||
|
|
||||||
if (t < halvePeriod[activeDac])
|
if (t < halvePeriod[activeDac])
|
||||||
dac0_5V.setInputCode(((t * amplitude[activeDac]) / halvePeriod[activeDac] )+ offset[activeDac]);
|
dac0_5V.setInputCode(((t * amplitude[activeDac]) / halvePeriod[activeDac]));
|
||||||
else
|
else
|
||||||
dac0_5V.setInputCode((((period[activeDac] - t) * (amplitude[activeDac]) / halvePeriod[activeDac])+offset[activeDac]));
|
dac0_5V.setInputCode((((period[activeDac] - t) * (amplitude[activeDac]) / halvePeriod[activeDac]) ));
|
||||||
}
|
}
|
||||||
else if (activeDac == 1 && dacOn[activeDac] == 1)
|
else if (activeDac == 1 && dacOn[activeDac] == 1)
|
||||||
{
|
{
|
||||||
@ -583,10 +569,10 @@ chars += Serial.print(adc0Reading);
|
|||||||
break;
|
break;
|
||||||
case 'r':
|
case 'r':
|
||||||
if (activeDac == 0 && dacOn[activeDac] == 1)
|
if (activeDac == 0 && dacOn[activeDac] == 1)
|
||||||
dac0_5V.setInputCode(random(amplitude[activeDac]) + offset[activeDac]);
|
dac0_5V.setInputCode(random(amplitude[activeDac]) );
|
||||||
else if (activeDac == 1 && dacOn[activeDac] == 1)
|
else if (activeDac == 1 && dacOn[activeDac] == 1)
|
||||||
{
|
{
|
||||||
dac1_8V.setInputCode(random(amplitude[activeDac]) + offset[activeDac]);
|
dac1_8V.setInputCode(random(amplitude[activeDac]) );
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 'z': // zero
|
case 'z': // zero
|
||||||
@ -596,13 +582,13 @@ chars += Serial.print(adc0Reading);
|
|||||||
dac1_8V.setInputCode(offset[activeDac]);
|
dac1_8V.setInputCode(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/0 = dac 0 0-5V (togg)\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/1 = dac 1 +-8V (togg)\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 (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\tx = exit\t\t \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
|
||||||
@ -638,7 +624,7 @@ chars += Serial.print(adc0Reading);
|
|||||||
;
|
;
|
||||||
a = Serial.read();
|
a = Serial.read();
|
||||||
|
|
||||||
if (a == '.')
|
if (a == '.')
|
||||||
{
|
{
|
||||||
while (Serial.available() == 0)
|
while (Serial.available() == 0)
|
||||||
;
|
;
|
||||||
@ -746,7 +732,6 @@ chars += Serial.print(adc0Reading);
|
|||||||
|
|
||||||
Serial.print(aC);
|
Serial.print(aC);
|
||||||
|
|
||||||
|
|
||||||
if (o >= 48 && o <= 53)
|
if (o >= 48 && o <= 53)
|
||||||
{
|
{
|
||||||
|
|
||||||
@ -765,7 +750,6 @@ chars += Serial.print(adc0Reading);
|
|||||||
o = Serial.read();
|
o = Serial.read();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
if (o >= 48 && o <= 57)
|
if (o >= 48 && o <= 57)
|
||||||
{
|
{
|
||||||
Serial.print((char)o);
|
Serial.print((char)o);
|
||||||
@ -870,8 +854,10 @@ chars += Serial.print(adc0Reading);
|
|||||||
// refillTable(0, offset[activeDac] + calib[1], 1);
|
// refillTable(0, offset[activeDac] + calib[1], 1);
|
||||||
setDac1_8V(((amplitude[activeDac] + calib[1]) / 276) - ((offset[activeDac] / 276) - 7));
|
setDac1_8V(((amplitude[activeDac] + calib[1]) / 276) - ((offset[activeDac] / 276) - 7));
|
||||||
mode[2] = 'v';
|
mode[2] = 'v';
|
||||||
} else if (mode[2] == 'v') {
|
}
|
||||||
//mode[2] = 's';
|
else if (mode[2] == 'v')
|
||||||
|
{
|
||||||
|
// mode[2] = 's';
|
||||||
}
|
}
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
@ -19,14 +19,10 @@
|
|||||||
#include <EEPROM.h>
|
#include <EEPROM.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#ifdef PIOSTUFF
|
#ifdef PIOSTUFF
|
||||||
#include "CH446Q.h"
|
#include "CH446Q.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#include "FileParsing.h"
|
#include "FileParsing.h"
|
||||||
|
|
||||||
#ifdef FSSTUFF
|
#ifdef FSSTUFF
|
||||||
@ -34,6 +30,8 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// https://wokwi.com/projects/367384677537829889
|
// https://wokwi.com/projects/367384677537829889
|
||||||
|
|
||||||
// nanoStatus nano;
|
// nanoStatus nano;
|
||||||
@ -41,13 +39,15 @@ const char *definesToChar(int); // i really need to find a way to not need to fo
|
|||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
|
//
|
||||||
|
|
||||||
//
|
//
|
||||||
// initArduino();
|
// initArduino();
|
||||||
debugFlagInit();
|
debugFlagInit();
|
||||||
|
|
||||||
#ifdef EEPROMSTUFF
|
#ifdef EEPROMSTUFF
|
||||||
EEPROM.begin(256);
|
EEPROM.begin(256);
|
||||||
|
debugFlagInit();
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
#ifdef PIOSTUFF
|
#ifdef PIOSTUFF
|
||||||
@ -59,65 +59,24 @@ debugFlagInit();
|
|||||||
initINA219();
|
initINA219();
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
|
|
||||||
initLEDs();
|
|
||||||
|
|
||||||
#ifdef FSSTUFF
|
#ifdef FSSTUFF
|
||||||
LittleFS.begin();
|
LittleFS.begin();
|
||||||
#endif
|
#endif
|
||||||
|
setDac0_5V(0.0);
|
||||||
lightUpRail(-1, 1, 220);
|
|
||||||
|
|
||||||
// if (EEPROM.read(CLEARBEFORECOMMANDADDRESS) == 0)
|
|
||||||
//{
|
|
||||||
#ifdef FSSTUFF5
|
|
||||||
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();
|
|
||||||
#ifdef PIOSTUFF
|
|
||||||
sendAllPaths();
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
while (Serial.available() > 0)
|
|
||||||
{
|
|
||||||
Serial.read();
|
|
||||||
delay(1);
|
|
||||||
}
|
|
||||||
|
|
||||||
delay(20);
|
|
||||||
}
|
|
||||||
//} else
|
|
||||||
// {
|
|
||||||
// delay(20);
|
|
||||||
//}
|
|
||||||
|
|
||||||
|
|
||||||
// parseWokwiFileToNodeFile();
|
|
||||||
// openNodeFile();
|
|
||||||
// while(1);
|
|
||||||
// lastCommandRead();
|
|
||||||
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void setup1()
|
||||||
|
{
|
||||||
|
|
||||||
|
initLEDs();
|
||||||
|
lightUpRail(-1, 1, 220);
|
||||||
|
|
||||||
|
}
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
|
|
||||||
@ -139,7 +98,7 @@ void loop()
|
|||||||
menu:
|
menu:
|
||||||
|
|
||||||
// arduinoPrint();
|
// arduinoPrint();
|
||||||
|
delay(10);
|
||||||
Serial.print("\n\n\r\t\t\tMenu\n\n\r");
|
Serial.print("\n\n\r\t\t\tMenu\n\n\r");
|
||||||
Serial.print("\tn = show netlist\n\r");
|
Serial.print("\tn = show netlist\n\r");
|
||||||
Serial.print("\tb = show bridge array\n\r");
|
Serial.print("\tb = show bridge array\n\r");
|
||||||
@ -352,6 +311,7 @@ menu:
|
|||||||
// lastCommandWrite(input);
|
// lastCommandWrite(input);
|
||||||
|
|
||||||
debugFlags:
|
debugFlags:
|
||||||
|
|
||||||
Serial.print("\n\r0. all off");
|
Serial.print("\n\r0. all off");
|
||||||
Serial.print("\n\r9. all on");
|
Serial.print("\n\r9. all on");
|
||||||
Serial.print("\n\ra-z. exit\n\r");
|
Serial.print("\n\ra-z. exit\n\r");
|
||||||
@ -379,14 +339,20 @@ menu:
|
|||||||
;
|
;
|
||||||
|
|
||||||
int toggleDebug = Serial.read();
|
int toggleDebug = Serial.read();
|
||||||
|
Serial.write(toggleDebug);
|
||||||
toggleDebug -= '0';
|
toggleDebug -= '0';
|
||||||
|
//Serial.print(toggleDebug);
|
||||||
if (toggleDebug >= 0 && toggleDebug <= 9)
|
if (toggleDebug >= 0 && toggleDebug <= 9)
|
||||||
{
|
{
|
||||||
|
|
||||||
#ifdef EEPROMSTUFF
|
#ifdef EEPROMSTUFF
|
||||||
debugFlagSet(toggleDebug);
|
debugFlagSet(toggleDebug);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
delay(10);
|
||||||
|
|
||||||
goto debugFlags;
|
goto debugFlags;
|
||||||
|
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
@ -412,3 +378,16 @@ menu:
|
|||||||
// waveGen();
|
// waveGen();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void loop1()
|
||||||
|
{
|
||||||
|
if (showLEDsCore2 == 1)
|
||||||
|
{
|
||||||
|
leds.show();
|
||||||
|
delayMicroseconds(900);
|
||||||
|
showLEDsCore2 = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
}
|
Loading…
x
Reference in New Issue
Block a user