mirror of
https://github.com/Architeuthis-Flux/Jumperless.git
synced 2024-11-23 23:00:57 +01:00
Better probing menu, disambuguation of shorted rows, add a flag to swap probe/button pins
This commit is contained in:
parent
85a915fb72
commit
022b511062
@ -10,12 +10,7 @@
|
||||
#include "LEDs.h"
|
||||
#include <EEPROM.h>
|
||||
#include "MachineCommands.h"
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
#include "Probing.h"
|
||||
|
||||
bool debugFP = EEPROM.read(DEBUG_FILEPARSINGADDRESS);
|
||||
bool debugFPtime = EEPROM.read(TIME_FILEPARSINGADDRESS);
|
||||
@ -29,7 +24,6 @@ char inputBuffer[INPUTBUFFERLENGTH] = {0};
|
||||
|
||||
ArduinoJson::StaticJsonDocument<8000> wokwiJson;
|
||||
|
||||
|
||||
String connectionsW[MAX_BRIDGES][5];
|
||||
|
||||
File nodeFile;
|
||||
@ -38,8 +32,6 @@ File wokwiFile;
|
||||
|
||||
unsigned long timeToFP = 0;
|
||||
|
||||
|
||||
|
||||
void savePreformattedNodeFile(int source)
|
||||
{
|
||||
LittleFS.remove("nodeFile.txt");
|
||||
@ -82,6 +74,11 @@ void savePreformattedNodeFile(int source)
|
||||
delay(1);
|
||||
}
|
||||
}
|
||||
// nodeFile.write("\n\r");
|
||||
|
||||
// nodeFile.seek(0);
|
||||
// nodeFileString.read(nodeFile);
|
||||
// Serial.println(nodeFileString);
|
||||
|
||||
nodeFile.close();
|
||||
}
|
||||
@ -91,26 +88,63 @@ void printNodeFile(void)
|
||||
nodeFile = LittleFS.open("nodeFile.txt", "r");
|
||||
if (!nodeFile)
|
||||
{
|
||||
if (debugFP)
|
||||
Serial.println("Failed to open nodeFile");
|
||||
// if (debugFP)
|
||||
// Serial.println("Failed to open nodeFile");
|
||||
return;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (debugFP)
|
||||
Serial.println("\n\ropened nodeFile.txt\n\n\rloading bridges from file\n\r");
|
||||
// if (debugFP)
|
||||
// Serial.println("\n\ropened nodeFile.txt\n\n\rloading bridges from file\n\r");
|
||||
}
|
||||
nodeFileString.clear();
|
||||
|
||||
nodeFileString.read(nodeFile);
|
||||
|
||||
nodeFile.close();
|
||||
// Serial.print(nodeFileString);
|
||||
|
||||
Serial.println(nodeFileString);
|
||||
// int newLines = 0;
|
||||
// Serial.println(nodeFileString.indexOf(","));
|
||||
// Serial.println(nodeFileString.charAt(nodeFileString.indexOf(",")+1));
|
||||
// Serial.println(nodeFileString.indexOf(","));
|
||||
|
||||
nodeFileString.clear();
|
||||
if (nodeFileString.charAt(nodeFileString.indexOf(",") + 1) != '\n')
|
||||
{
|
||||
nodeFileString.replace(",", ",\n\r");
|
||||
nodeFileString.replace("{", "{\n\r");
|
||||
}
|
||||
|
||||
// int nodeFileStringLength = nodeFileString.indexOf("}");
|
||||
// if (nodeFileStringLength != -1)
|
||||
// {
|
||||
// //nodeFileString.remove(nodeFileStringLength + 1, -1);
|
||||
// }
|
||||
|
||||
// if (nodeFileString.indexOf(",\n\r") == -1)
|
||||
// {
|
||||
// nodeFileString.replace(",", ",\n\r");
|
||||
// nodeFileString.replace("{", "{\n\r");
|
||||
// }
|
||||
|
||||
// nodeFile.close();
|
||||
|
||||
int nodeFileStringLength = nodeFileString.indexOf("}");
|
||||
if (nodeFileStringLength != -1)
|
||||
{
|
||||
if (nodeFileString.charAt(nodeFileStringLength + 1) != '\n')
|
||||
{
|
||||
nodeFileString.replace("}", "}\n\r");
|
||||
}
|
||||
nodeFileString.remove(nodeFileStringLength + 2, -1);
|
||||
}
|
||||
|
||||
// nodeFileString.readUntilToken(nodeFileString, "{");
|
||||
// nodeFileString.removeLast(9);
|
||||
|
||||
Serial.print(nodeFileString);
|
||||
// Serial.print('*');
|
||||
nodeFileString.clear();
|
||||
}
|
||||
|
||||
void parseWokwiFileToNodeFile(void)
|
||||
{
|
||||
@ -410,7 +444,6 @@ void clearNodeFile(void)
|
||||
void removeBridgeFromNodeFile(int node1, int node2)
|
||||
{
|
||||
|
||||
|
||||
nodeFile = LittleFS.open("nodeFile.txt", "r+");
|
||||
if (!nodeFile)
|
||||
{
|
||||
@ -423,38 +456,136 @@ void removeBridgeFromNodeFile(int node1, int node2)
|
||||
if (debugFP)
|
||||
Serial.println("\n\ropened nodeFile.txt\n\n\rloading bridges from file\n\r");
|
||||
}
|
||||
char nodeAsChar[20];
|
||||
|
||||
nodeFileString.clear();
|
||||
|
||||
nodeFileString.read(nodeFile);
|
||||
nodeFile.close();
|
||||
|
||||
char nodeAsChar[20];
|
||||
itoa(node1, nodeAsChar, 10);
|
||||
char paddedChar[21];
|
||||
|
||||
if (node2 != -1)
|
||||
paddedChar[0] = ' ';
|
||||
for (int i = 1; i < 20; i++)
|
||||
{
|
||||
nodeFileString.replace(nodeAsChar, "x");
|
||||
itoa(node2, nodeAsChar, 10);
|
||||
nodeFileString.replace(nodeAsChar, "x");
|
||||
if (nodeAsChar[i - 1] == '\0')
|
||||
{
|
||||
paddedChar[i] = ' ';
|
||||
paddedChar[i + 1] = '\0';
|
||||
break;
|
||||
}
|
||||
paddedChar[i] = nodeAsChar[i - 1];
|
||||
}
|
||||
|
||||
int numberOfLines = 0;
|
||||
// Serial.print(paddedChar);
|
||||
// Serial.println("*");
|
||||
|
||||
char lines[100][20];
|
||||
|
||||
int lineIndex = 0;
|
||||
int charIndex = 0;
|
||||
|
||||
for (int i = 0; i < 100; i++)
|
||||
{
|
||||
|
||||
if (nodeFileString[charIndex] == '\0')
|
||||
{
|
||||
numberOfLines = i;
|
||||
break;
|
||||
}
|
||||
lines[i][0] = ' ';
|
||||
for (int j = 1; j < 20; j++)
|
||||
{
|
||||
if (nodeFileString[charIndex] == ',')
|
||||
{
|
||||
lines[i][j] = ' ';
|
||||
lines[i][j + 1] = ',';
|
||||
// lines[i][j + 2] = '\n';
|
||||
// lines[i][j + 3] = '\r';
|
||||
lines[i][j + 2] = '\0';
|
||||
|
||||
charIndex++;
|
||||
break;
|
||||
}
|
||||
else if (nodeFileString[charIndex] == '-')
|
||||
{
|
||||
lines[i][j] = ' ';
|
||||
lines[i][j + 1] = '-';
|
||||
lines[i][j + 2] = ' ';
|
||||
j += 2;
|
||||
charIndex++;
|
||||
// break;
|
||||
}
|
||||
else if (nodeFileString[charIndex] == '\n' || nodeFileString[charIndex] == '\r' || nodeFileString[charIndex] == '{' || nodeFileString[charIndex] == '}')
|
||||
{
|
||||
lines[i][j] = ' ';
|
||||
charIndex++;
|
||||
}
|
||||
else
|
||||
{
|
||||
nodeFileString.replace(nodeAsChar, "x");
|
||||
lines[i][j] = nodeFileString[charIndex];
|
||||
charIndex++;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
nodeFileString.replace("x-x,", "");
|
||||
// Serial.println("\n\r********");
|
||||
|
||||
for (int i = 0; i < numberOfLines; i++)
|
||||
{
|
||||
if (lines[i][0] == '\0')
|
||||
{
|
||||
// break;
|
||||
}
|
||||
if (strstr(lines[i], paddedChar) != NULL)
|
||||
{
|
||||
// Serial.println(lines[i]);
|
||||
// delay(1);
|
||||
|
||||
//Serial.println(nodeAsChar);
|
||||
for (int j = 0; j < 18; j++)
|
||||
{
|
||||
lines[i][j] = ' ';
|
||||
}
|
||||
// lines[i][18] = '\n';
|
||||
// lines[i][19] = '\r';
|
||||
lines[i][0] = '\0';
|
||||
}
|
||||
}
|
||||
|
||||
nodeFileString.clear();
|
||||
nodeFileString.concat("{");
|
||||
for (int i = 0; i < numberOfLines; i++)
|
||||
{
|
||||
if (lines[i][0] == '\0')
|
||||
{
|
||||
continue;
|
||||
}
|
||||
// Serial.println(i);
|
||||
// delay(1);
|
||||
for (int j = 0; j < 20; j++)
|
||||
{
|
||||
if (lines[i][j] == '\0')
|
||||
{
|
||||
break;
|
||||
}
|
||||
if (lines[i][j] == ' ')
|
||||
{
|
||||
continue;
|
||||
}
|
||||
nodeFileString.concat(lines[i][j]);
|
||||
// Serial.print(lines[i][j]);
|
||||
// delay(1);
|
||||
}
|
||||
}
|
||||
nodeFileString.concat("}\n\r");
|
||||
|
||||
//Serial.println(nodeFileString);
|
||||
|
||||
nodeFile.close();
|
||||
nodeFile = LittleFS.open("nodeFile.txt", "w+");
|
||||
nodeFile.write(nodeFileString.c_str());
|
||||
|
||||
nodeFile.close();
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
void addBridgeToNodeFile(int node1, int node2)
|
||||
@ -482,7 +613,9 @@ while (nodeFile.available())
|
||||
if (c == '}')
|
||||
{
|
||||
break;
|
||||
} else {
|
||||
}
|
||||
else
|
||||
{
|
||||
nodeFileBraceIndex++;
|
||||
}
|
||||
|
||||
@ -493,7 +626,22 @@ while (nodeFile.available())
|
||||
nodeFile.print(node1);
|
||||
nodeFile.print("-");
|
||||
nodeFile.print(node2);
|
||||
nodeFile.print(",\n\r}\n\r{\n\r}\n\r");
|
||||
nodeFile.print(",\n\r}\n\r");
|
||||
|
||||
// if (1)
|
||||
// {
|
||||
// Serial.println("wrote to nodeFile.txt");
|
||||
|
||||
// Serial.println("nodeFile.txt contents:\n\r");
|
||||
// nodeFile.seek(0);
|
||||
|
||||
// while (nodeFile.available())
|
||||
// {
|
||||
// Serial.write(nodeFile.read());
|
||||
// }
|
||||
// Serial.println("\n\r");
|
||||
// }
|
||||
// Serial.print (nodeFile);
|
||||
nodeFile.close();
|
||||
return;
|
||||
}
|
||||
@ -504,7 +652,7 @@ nodeFile.seek(nodeFileBraceIndex);
|
||||
nodeFile.print(node1);
|
||||
nodeFile.print("-");
|
||||
nodeFile.print(node2);
|
||||
nodeFile.print(",\n\r}\n\r{\n\r}\n\r");
|
||||
nodeFile.print(",}\n\r");
|
||||
|
||||
if (debugFP)
|
||||
{
|
||||
@ -520,10 +668,8 @@ nodeFile.seek(nodeFileBraceIndex);
|
||||
Serial.println("\n\r");
|
||||
}
|
||||
nodeFile.close();
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
void writeToNodeFile(void)
|
||||
{
|
||||
|
||||
@ -565,7 +711,7 @@ void writeToNodeFile(void)
|
||||
nodeFile.print(connectionsW[i][1]);
|
||||
nodeFile.print(",\n\r");
|
||||
}
|
||||
nodeFile.print("}\n\r");
|
||||
nodeFile.print("\n\r}\n\r");
|
||||
|
||||
if (debugFP)
|
||||
{
|
||||
@ -600,6 +746,7 @@ void openNodeFile()
|
||||
Serial.println("\n\ropened nodeFile.txt\n\n\rloading bridges from file\n\r");
|
||||
}
|
||||
|
||||
nodeFileString.clear();
|
||||
nodeFileString.read(nodeFile);
|
||||
|
||||
nodeFile.close();
|
||||
@ -658,7 +805,7 @@ void splitStringToFields()
|
||||
}
|
||||
else
|
||||
{
|
||||
nodeFileString.substring(specialFunctionsString, 0, nodeFileString.length());
|
||||
nodeFileString.substring(specialFunctionsString, 0, -1); // nodeFileString.length());
|
||||
}
|
||||
specialFunctionsString.trim();
|
||||
|
||||
@ -693,7 +840,6 @@ void replaceSFNamesWithDefinedInts(void)
|
||||
Serial.println(specialFunctionsString);
|
||||
}
|
||||
|
||||
|
||||
specialFunctionsString.replace("GND", "100");
|
||||
specialFunctionsString.replace("GROUND", "100");
|
||||
specialFunctionsString.replace("SUPPLY_5V", "105");
|
||||
@ -857,7 +1003,6 @@ void parseStringToBridges(void)
|
||||
// Serial.print("stringIndex = ");
|
||||
// Serial.println(stringIndex);
|
||||
|
||||
|
||||
buffer.toInt(path[newBridgeIndex].node1);
|
||||
|
||||
// Serial.print("path[newBridgeIndex].node1 = ");
|
||||
@ -978,6 +1123,8 @@ void debugFlagInit(void)
|
||||
EEPROM.write(LEDBRIGHTNESSADDRESS, DEFAULTBRIGHTNESS);
|
||||
EEPROM.write(RAILBRIGHTNESSADDRESS, DEFAULTRAILBRIGHTNESS);
|
||||
EEPROM.write(SPECIALBRIGHTNESSADDRESS, DEFAULTSPECIALNETBRIGHTNESS);
|
||||
EEPROM.write(PROBESWAPADDRESS, 0);
|
||||
|
||||
|
||||
EEPROM.commit();
|
||||
delay(5);
|
||||
@ -999,6 +1146,8 @@ void debugFlagInit(void)
|
||||
|
||||
debugLEDs = EEPROM.read(DEBUG_LEDSADDRESS);
|
||||
|
||||
probeSwap = EEPROM.read(PROBESWAPADDRESS);
|
||||
|
||||
#else
|
||||
|
||||
debugFP = 1;
|
||||
@ -1079,26 +1228,8 @@ void debugFlagSet(int flag)
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
case 2:
|
||||
{
|
||||
flagStatus = EEPROM.read(TIME_FILEPARSINGADDRESS);
|
||||
|
||||
if (flagStatus == 0)
|
||||
{
|
||||
EEPROM.write(TIME_FILEPARSINGADDRESS, 1);
|
||||
|
||||
debugFPtime = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
EEPROM.write(TIME_FILEPARSINGADDRESS, 0);
|
||||
|
||||
debugFPtime = false;
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
case 3:
|
||||
{
|
||||
flagStatus = EEPROM.read(DEBUG_NETMANAGERADDRESS);
|
||||
|
||||
@ -1116,25 +1247,8 @@ void debugFlagSet(int flag)
|
||||
}
|
||||
break;
|
||||
}
|
||||
case 4:
|
||||
{
|
||||
flagStatus = EEPROM.read(TIME_NETMANAGERADDRESS);
|
||||
|
||||
if (flagStatus == 0)
|
||||
{
|
||||
EEPROM.write(TIME_NETMANAGERADDRESS, 1);
|
||||
|
||||
debugNMtime = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
EEPROM.write(TIME_NETMANAGERADDRESS, 0);
|
||||
|
||||
debugNMtime = false;
|
||||
}
|
||||
break;
|
||||
}
|
||||
case 5:
|
||||
case 3:
|
||||
{
|
||||
flagStatus = EEPROM.read(DEBUG_NETTOCHIPCONNECTIONSADDRESS);
|
||||
|
||||
@ -1153,7 +1267,7 @@ void debugFlagSet(int flag)
|
||||
|
||||
break;
|
||||
}
|
||||
case 6:
|
||||
case 4:
|
||||
{
|
||||
flagStatus = EEPROM.read(DEBUG_NETTOCHIPCONNECTIONSALTADDRESS);
|
||||
|
||||
@ -1172,7 +1286,7 @@ void debugFlagSet(int flag)
|
||||
break;
|
||||
}
|
||||
|
||||
case 7:
|
||||
case 5:
|
||||
{
|
||||
flagStatus = EEPROM.read(DEBUG_LEDSADDRESS);
|
||||
|
||||
@ -1191,6 +1305,25 @@ void debugFlagSet(int flag)
|
||||
break;
|
||||
}
|
||||
|
||||
case 6:
|
||||
{
|
||||
flagStatus = EEPROM.read(PROBESWAPADDRESS);
|
||||
|
||||
if (flagStatus == 0)
|
||||
{
|
||||
EEPROM.write(PROBESWAPADDRESS, 1);
|
||||
|
||||
probeSwap = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
EEPROM.write(PROBESWAPADDRESS, 0);
|
||||
|
||||
probeSwap = false;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case 0:
|
||||
{
|
||||
EEPROM.write(DEBUG_FILEPARSINGADDRESS, 0);
|
||||
@ -1200,6 +1333,7 @@ void debugFlagSet(int flag)
|
||||
EEPROM.write(DEBUG_NETTOCHIPCONNECTIONSADDRESS, 0);
|
||||
EEPROM.write(DEBUG_NETTOCHIPCONNECTIONSALTADDRESS, 0);
|
||||
EEPROM.write(DEBUG_LEDSADDRESS, 0);
|
||||
|
||||
debugFP = false;
|
||||
debugFPtime = false;
|
||||
debugNM = false;
|
||||
@ -1207,6 +1341,7 @@ void debugFlagSet(int flag)
|
||||
debugNTCC = false;
|
||||
debugNTCC2 = false;
|
||||
debugLEDs = false;
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -27,8 +27,9 @@ extern volatile int sendAllPathsCore2;
|
||||
#define LEDBRIGHTNESSADDRESS 39
|
||||
#define RAILBRIGHTNESSADDRESS 40
|
||||
#define SPECIALBRIGHTNESSADDRESS 41
|
||||
#define PROBESWAPADDRESS 42
|
||||
|
||||
#define FIRSTSTARTUPADDRESS 42
|
||||
#define FIRSTSTARTUPADDRESS 43
|
||||
|
||||
|
||||
|
||||
|
@ -117,7 +117,7 @@ void clearLEDs(void);
|
||||
void randomColors(uint32_t color, int wait);
|
||||
void rainbowy(int ,int, int wait);
|
||||
void showNets(void);
|
||||
void assignNetColors (void);
|
||||
void assignNetColors ();
|
||||
void lightUpRail (int logo = -1, int railNumber = -1, int onOff = 1, int brightness = DEFAULTRAILBRIGHTNESS, int supplySwitchPosition= 1);
|
||||
|
||||
void lightUpNet (int netNumber = 0 , int node = -1, int onOff = 1, int brightness = DEFAULTBRIGHTNESS, int hueShift = 0);//-1 means all nodes (default)
|
||||
|
@ -10,10 +10,13 @@
|
||||
#include "NetManager.h"
|
||||
#include "Probing.h"
|
||||
#include "AdcUsb.h"
|
||||
|
||||
#include <algorithm>
|
||||
#include "pico/stdlib.h"
|
||||
#include "hardware/pwm.h"
|
||||
#include <EEPROM.h>
|
||||
|
||||
|
||||
int probeSwap = 0;
|
||||
int probeHalfPeriodus = 20;
|
||||
|
||||
unsigned long probingTimer = 0;
|
||||
@ -35,8 +38,13 @@ int nodesToConnect[2] = {-1, -1};
|
||||
|
||||
int node1or2 = 0;
|
||||
|
||||
int probePin = 19;
|
||||
int buttonPin = 18;
|
||||
|
||||
|
||||
|
||||
int rainbowList[13][3] = {
|
||||
{45, 45, 45},
|
||||
{55, 55, 55},
|
||||
{10, 45, 30},
|
||||
{30, 15, 45},
|
||||
{8, 27, 45},
|
||||
@ -58,22 +66,23 @@ int justCleared = 1;
|
||||
int probeMode(int pin, int setOrClear)
|
||||
{
|
||||
|
||||
probeSwap = EEPROM.read(PROBESWAPADDRESS);
|
||||
|
||||
|
||||
if (probeSwap == 0)
|
||||
{
|
||||
probePin = 19;
|
||||
buttonPin = 18;
|
||||
|
||||
} else
|
||||
{
|
||||
probePin = 18;
|
||||
buttonPin = 19;
|
||||
}
|
||||
restartProbing:
|
||||
int lastRow[10];
|
||||
|
||||
int pokedNumber = 0;
|
||||
Serial.print("Press any key to exit and commit paths (or touch probe to gpio 18) ");
|
||||
if (setOrClear == 1)
|
||||
{
|
||||
Serial.print("Set bridges\n\n\n\r");
|
||||
rawOtherColors[1] = 0x4500e8;
|
||||
rainbowIndex = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
Serial.print("Clear bridges\n\n\n\r");
|
||||
rawOtherColors[1] = 0x8855A8;
|
||||
rainbowIndex = 12;
|
||||
}
|
||||
|
||||
// Serial.print(numberOfNets);
|
||||
|
||||
@ -96,16 +105,42 @@ int probeMode(int pin, int setOrClear)
|
||||
|
||||
int row[16] = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
|
||||
|
||||
row[1] = -2;
|
||||
probeTimeout = millis();
|
||||
|
||||
int readPercentage[101];
|
||||
probingTimer = millis();
|
||||
|
||||
// Serial.print("Press any key to exit and commit paths (or touch probe to gpio 18) ");
|
||||
Serial.print("\n\r\t Probing mode\n\n\r");
|
||||
Serial.print(" long press = connect (pink) / clear (orange)\n\r");
|
||||
Serial.print(" short press = commit\n\r");
|
||||
|
||||
if (setOrClear == 1)
|
||||
{
|
||||
Serial.print("\n\r\t connect nodes\n\n\n\r");
|
||||
rawOtherColors[1] = 0x4500e8;
|
||||
rainbowIndex = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
Serial.print("\n\r\t clear nodes\n\n\n\r");
|
||||
rawOtherColors[1] = 0x6644A8;
|
||||
rainbowIndex = 12;
|
||||
}
|
||||
|
||||
unsigned long probeButtonTimer = 0;
|
||||
|
||||
if (setOrClear == 0)
|
||||
{
|
||||
delay(1000);
|
||||
probeButtonTimer = millis();
|
||||
|
||||
// probingTimer = millis() -400;
|
||||
}
|
||||
|
||||
unsigned long doubleSelectTimeout = millis();
|
||||
int doubleSelectCountdown = 0;
|
||||
|
||||
while (Serial.available() == 0 && (millis() - probeTimeout) < 6200)
|
||||
{
|
||||
delayMicroseconds(38000);
|
||||
@ -114,26 +149,41 @@ int probeMode(int pin, int setOrClear)
|
||||
|
||||
row[0] = scanRows(ADC0_PIN);
|
||||
|
||||
if (row[0] == -18 && millis() - probingTimer > 500 && checkProbeButton() == 1)
|
||||
if (row[0] == -18 && (millis() - probingTimer > 500) && checkProbeButton() == 1 && millis() - probeButtonTimer > 1500)
|
||||
{
|
||||
if (longShortPress(1000) == 1)
|
||||
{
|
||||
setOrClear = !setOrClear;
|
||||
probingTimer = millis();
|
||||
goto restartProbing;
|
||||
break;
|
||||
}
|
||||
|
||||
// Serial.print("\n\rCommitting paths!\n\r");
|
||||
// probingTimer = millis();
|
||||
row[1] = -2;
|
||||
probingTimer = millis();
|
||||
|
||||
connectedRowsIndex = 0;
|
||||
|
||||
|
||||
node1or2 = 0;
|
||||
nodesToConnect[0] = -1;
|
||||
nodesToConnect[1] = -1;
|
||||
|
||||
// if (node1or2 == 1)
|
||||
// {
|
||||
// leds.setPixelColor(nodesToPixelMap[nodesToConnect[0]], 0, 0, 0);
|
||||
//showLEDsCore2 = 1;
|
||||
// nodesToConnect[0] = -1;
|
||||
// nodesToConnect[1] = -1;
|
||||
// }
|
||||
|
||||
|
||||
|
||||
break;
|
||||
}
|
||||
else
|
||||
{
|
||||
// probingTimer = millis();
|
||||
}
|
||||
|
||||
if (row[0] != -1 && row[0] != row[1])
|
||||
{
|
||||
row[1] = row[0];
|
||||
|
||||
// row[1] = row[0];
|
||||
|
||||
if (connectedRowsIndex > 1)
|
||||
{
|
||||
@ -162,14 +212,20 @@ int probeMode(int pin, int setOrClear)
|
||||
}
|
||||
connectedRowsIndex = connectedRows2Index[maxIndex];
|
||||
|
||||
std::sort(connectedRows, connectedRows + connectedRowsIndex);
|
||||
|
||||
nodesToConnect[node1or2] = selectFromLastFound();
|
||||
|
||||
node1or2++;
|
||||
probingTimer = millis();
|
||||
// showLEDsCore2 = 1;
|
||||
delay(30);
|
||||
}
|
||||
else if (connectedRowsIndex == 1)
|
||||
{
|
||||
nodesToConnect[node1or2] = connectedRows[0];
|
||||
|
||||
printNodeOrName(nodesToConnect[0]);
|
||||
Serial.print("\r\t");
|
||||
if (node1or2 == 1 && setOrClear == 1 && nodesToConnect[0] == GND)
|
||||
{
|
||||
leds.setPixelColor(nodesToPixelMap[nodesToConnect[1]], 0, 45, 5);
|
||||
@ -186,27 +242,35 @@ int probeMode(int pin, int setOrClear)
|
||||
{
|
||||
leds.setPixelColor(nodesToPixelMap[nodesToConnect[0]], 45, 5, 0);
|
||||
}
|
||||
|
||||
else
|
||||
{
|
||||
// Serial.print("!!!!!");
|
||||
leds.setPixelColor(nodesToPixelMap[connectedRows[0]], rainbowList[rainbowIndex][0], rainbowList[rainbowIndex][1], rainbowList[rainbowIndex][2]);
|
||||
// leds.show();
|
||||
}
|
||||
|
||||
node1or2++;
|
||||
probingTimer = millis();
|
||||
showLEDsCore2 = 1;
|
||||
showLEDsCore2 = 2;
|
||||
delay(10);
|
||||
|
||||
// delay(3);
|
||||
}
|
||||
if (node1or2 == 1)
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
if (node1or2 >= 2)
|
||||
if (node1or2 >= 2 || (setOrClear == 0 && node1or2 >= 1))
|
||||
{
|
||||
|
||||
if (setOrClear == 1)
|
||||
{
|
||||
Serial.print("\r \r");
|
||||
printNodeOrName(nodesToConnect[0]);
|
||||
Serial.print(" - ");
|
||||
printNodeOrName(nodesToConnect[1]);
|
||||
Serial.print("\t\t");
|
||||
if (setOrClear == 1)
|
||||
{
|
||||
Serial.print("Connected\n\r");
|
||||
Serial.print(" \t ");
|
||||
Serial.print("connected\n\r");
|
||||
addBridgeToNodeFile(nodesToConnect[0], nodesToConnect[1]);
|
||||
// rainbowIndex++;
|
||||
if (rainbowIndex > 1)
|
||||
@ -225,20 +289,33 @@ int probeMode(int pin, int setOrClear)
|
||||
// Serial.print("bridgesToPaths\n\r");
|
||||
// delay(18);
|
||||
// showNets();
|
||||
//showLEDsCore2 = 1;
|
||||
sendAllPathsCore2 = 1;
|
||||
showLEDsCore2 = 1;
|
||||
// digitalWrite(RESETPIN, HIGH);
|
||||
|
||||
// delayMicroseconds(10);
|
||||
|
||||
// sendAllPathsCore2 = 1;
|
||||
// digitalWrite(RESETPIN, LOW);
|
||||
delay(25);
|
||||
|
||||
// row[1] = -1;
|
||||
|
||||
// doubleSelectTimeout = millis();
|
||||
|
||||
doubleSelectTimeout = millis();
|
||||
doubleSelectCountdown = 2000;
|
||||
}
|
||||
else
|
||||
{
|
||||
Serial.print("Disconnected\n\r");
|
||||
removeBridgeFromNodeFile(nodesToConnect[0], nodesToConnect[1]);
|
||||
Serial.print("\r \r");
|
||||
printNodeOrName(nodesToConnect[0]);
|
||||
Serial.print("\t cleared\n\r");
|
||||
removeBridgeFromNodeFile(nodesToConnect[0]);
|
||||
leds.setPixelColor(nodesToPixelMap[nodesToConnect[0]], 0, 0, 0);
|
||||
|
||||
leds.setPixelColor(nodesToPixelMap[nodesToConnect[1]], 0, 0, 0);
|
||||
//leds.setPixelColor(nodesToPixelMap[nodesToConnect[1]], 0, 0, 0);
|
||||
rainbowIndex = 12;
|
||||
|
||||
//printNodeFile();
|
||||
clearAllNTCC();
|
||||
openNodeFile();
|
||||
getNodesToConnect();
|
||||
@ -250,28 +327,43 @@ int probeMode(int pin, int setOrClear)
|
||||
// Serial.print("bridgesToPaths\n\r");
|
||||
// delay(18);
|
||||
// showNets();
|
||||
//showLEDsCore2 = 1;
|
||||
sendAllPathsCore2 = 1;
|
||||
showLEDsCore2 = 1;
|
||||
// sendAllPathsCore2 = 1;
|
||||
// logoFlash = 1;
|
||||
delay(25);
|
||||
// row[1] = -1;
|
||||
}
|
||||
node1or2 = 0;
|
||||
nodesToConnect[0] = -1;
|
||||
nodesToConnect[1] = -1;
|
||||
} else if (node1or2 == 1)
|
||||
{
|
||||
|
||||
|
||||
// Serial.print(" ");
|
||||
|
||||
// row[1] = -2;
|
||||
doubleSelectTimeout = millis();
|
||||
doubleSelectCountdown = 2000;
|
||||
}
|
||||
|
||||
// Serial.print("\n\n\r");
|
||||
// delay(1000);
|
||||
|
||||
row[1] = row[0];
|
||||
}
|
||||
|
||||
if (node1or2 == 0 && doubleSelectCountdown <= 0)
|
||||
{
|
||||
|
||||
row[1] = -2;
|
||||
}
|
||||
|
||||
// Serial.println(doubleSelectCountdown);
|
||||
|
||||
if (doubleSelectCountdown <= 0)
|
||||
{
|
||||
|
||||
doubleSelectCountdown = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
doubleSelectCountdown = doubleSelectCountdown - (millis() - doubleSelectTimeout);
|
||||
|
||||
doubleSelectTimeout = millis();
|
||||
}
|
||||
|
||||
probeTimeout = millis();
|
||||
}
|
||||
digitalWrite(RESETPIN, LOW);
|
||||
@ -281,7 +373,7 @@ int probeMode(int pin, int setOrClear)
|
||||
|
||||
bridgesToPaths();
|
||||
// clearLEDs();
|
||||
//leds.clear();
|
||||
leds.clear();
|
||||
assignNetColors();
|
||||
// // Serial.print("bridgesToPaths\n\r");
|
||||
// delay(18);
|
||||
@ -292,8 +384,9 @@ showLEDsCore2 = 1;
|
||||
|
||||
sendAllPathsCore2 = 1;
|
||||
// delay(25);
|
||||
// pinMode(19, INPUT);
|
||||
// pinMode(probePin, INPUT);
|
||||
delay(300);
|
||||
row[1] = -2;
|
||||
|
||||
return 1;
|
||||
}
|
||||
@ -306,41 +399,70 @@ int selectFromLastFound(void)
|
||||
int selected = 0;
|
||||
int selectionConfirmed = 0;
|
||||
|
||||
Serial.print("\n\r");
|
||||
Serial.print(" multiple nodes found\n\n\r");
|
||||
Serial.print(" short press = cycle through nodes\n\r");
|
||||
Serial.print(" long press = select\n\r");
|
||||
|
||||
Serial.print("\n\r ");
|
||||
for (int i = 0; i < connectedRowsIndex; i++)
|
||||
{
|
||||
|
||||
printNodeOrName(connectedRows[i]);
|
||||
if (i < connectedRowsIndex - 1)
|
||||
{
|
||||
Serial.print(", ");
|
||||
}
|
||||
}
|
||||
Serial.print("\n\n\r ");
|
||||
|
||||
uint32_t previousColor[connectedRowsIndex];
|
||||
|
||||
for (int i = 0; i < connectedRowsIndex; i++)
|
||||
{
|
||||
previousColor[i] = leds.getPixelColor(nodesToPixelMap[connectedRows[i]]);
|
||||
}
|
||||
|
||||
while (selectionConfirmed == 0)
|
||||
{
|
||||
probeTimeout = millis();
|
||||
if (millis() - blinkTimer > 100)
|
||||
{
|
||||
// selected++;
|
||||
// if (selected >= lastFoundIndex[node1or2])
|
||||
// if (millis() - blinkTimer > 100)
|
||||
// {
|
||||
// selected = 0;
|
||||
// }
|
||||
|
||||
for (int i = 0; i < connectedRowsIndex; i++)
|
||||
{
|
||||
if (i == selected)
|
||||
{
|
||||
leds.setPixelColor(nodesToPixelMap[connectedRows[i]], rainbowList[rainbowIndex][0], rainbowList[rainbowIndex][1], rainbowList[rainbowIndex][2]);
|
||||
leds.setPixelColor(nodesToPixelMap[connectedRows[i]], rainbowList[0][0], rainbowList[0][1], rainbowList[0][2]);
|
||||
}
|
||||
else
|
||||
{
|
||||
leds.setPixelColor(nodesToPixelMap[connectedRows[i]], rainbowList[rainbowIndex][0] / 4, rainbowList[rainbowIndex][1] / 4, rainbowList[rainbowIndex][2] / 4);
|
||||
// uint32_t previousColor = leds.getPixelColor(nodesToPixelMap[connectedRows[i]]);
|
||||
if (previousColor[i] != 0)
|
||||
{
|
||||
int r = (previousColor[i] >> 16) & 0xFF;
|
||||
int g = (previousColor[i] >> 8) & 0xFF;
|
||||
int b = (previousColor[i] >> 0) & 0xFF;
|
||||
leds.setPixelColor(nodesToPixelMap[connectedRows[i]], (r / 3) + 3, (g / 3) + 3, (b / 3) + 3);
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
leds.setPixelColor(nodesToPixelMap[connectedRows[i]], rainbowList[0][0] / 8, rainbowList[0][1] / 8, rainbowList[0][2] / 8);
|
||||
}
|
||||
}
|
||||
showLEDsCore2 = 1;
|
||||
}
|
||||
Serial.print("\r");
|
||||
Serial.print("");
|
||||
printNodeOrName(connectedRows[selected]);
|
||||
Serial.print(" ");
|
||||
//leds.show();
|
||||
showLEDsCore2 = 2;
|
||||
blinkTimer = millis();
|
||||
}
|
||||
|
||||
// if (checkProbeButton() == 1)
|
||||
// {
|
||||
// delay(10);
|
||||
|
||||
// if (checkProbeButton() == 1)
|
||||
// {
|
||||
|
||||
// }
|
||||
delay(30);
|
||||
int longShort = longShortPress();
|
||||
|
||||
delay(5);
|
||||
if (longShort == 1)
|
||||
{
|
||||
selectionConfirmed = 1;
|
||||
@ -365,19 +487,16 @@ int selectFromLastFound(void)
|
||||
return selected2;
|
||||
// break;
|
||||
}
|
||||
else
|
||||
{
|
||||
selected++;
|
||||
blinkTimer = 0;
|
||||
while (1)
|
||||
else if (longShort == 0)
|
||||
{
|
||||
|
||||
if (checkProbeButton() == 1)
|
||||
{
|
||||
break;
|
||||
}
|
||||
delay(5);
|
||||
}
|
||||
selected++;
|
||||
blinkTimer = 0;
|
||||
|
||||
// break;
|
||||
//}
|
||||
// delay(5);
|
||||
|
||||
// Serial.print("\n\r");
|
||||
// Serial.print("node1or2: ");
|
||||
// Serial.println(node1or2);
|
||||
@ -393,15 +512,16 @@ int selectFromLastFound(void)
|
||||
|
||||
selected = 0;
|
||||
}
|
||||
delay(20);
|
||||
//delay(100);
|
||||
}
|
||||
delay(15);
|
||||
// }
|
||||
//}
|
||||
|
||||
// showLEDsCore2 = 1;
|
||||
}
|
||||
|
||||
return selected;
|
||||
int selected2 = connectedRows[selected];
|
||||
return selected2;
|
||||
}
|
||||
|
||||
int longShortPress(int pressLength)
|
||||
@ -411,6 +531,9 @@ int longShortPress(int pressLength)
|
||||
|
||||
clickTimer = millis();
|
||||
|
||||
if (checkProbeButton() == 1)
|
||||
{
|
||||
|
||||
while (millis() - clickTimer < pressLength)
|
||||
{
|
||||
if (checkProbeButton() == 0)
|
||||
@ -419,6 +542,11 @@ int longShortPress(int pressLength)
|
||||
}
|
||||
delay(5);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
return 1;
|
||||
}
|
||||
@ -429,7 +557,7 @@ int checkProbeButton(void)
|
||||
|
||||
startProbe();
|
||||
|
||||
if (readFloatingOrState(18, 0) == probe)
|
||||
if (readFloatingOrState(buttonPin, 0) == probe)
|
||||
{
|
||||
buttonState = 1;
|
||||
}
|
||||
@ -461,13 +589,13 @@ int readFloatingOrState(int pin, int rowBeingScanned)
|
||||
if (rowBeingScanned != -1)
|
||||
{
|
||||
|
||||
analogWrite(19, 128);
|
||||
analogWrite(probePin, 128);
|
||||
|
||||
while (1) // this is the silliest way to align to the falling edge of the probe PWM signal
|
||||
{
|
||||
if (gpio_get(19) != 0)
|
||||
if (gpio_get(probePin) != 0)
|
||||
{
|
||||
if (gpio_get(19) == 0)
|
||||
if (gpio_get(probePin) == 0)
|
||||
{
|
||||
break;
|
||||
}
|
||||
@ -489,9 +617,9 @@ int readFloatingOrState(int pin, int rowBeingScanned)
|
||||
{
|
||||
while (1) // this is the silliest way to align to the falling edge of the probe PWM signal
|
||||
{
|
||||
if (gpio_get(19) != 0)
|
||||
if (gpio_get(probePin) != 0)
|
||||
{
|
||||
if (gpio_get(19) == 0)
|
||||
if (gpio_get(probePin) == 0)
|
||||
{
|
||||
break;
|
||||
}
|
||||
@ -527,28 +655,36 @@ int readFloatingOrState(int pin, int rowBeingScanned)
|
||||
}
|
||||
else
|
||||
{
|
||||
// Serial.print(readingPullup);
|
||||
// Serial.print(readingPullup2);
|
||||
// Serial.print(readingPullup3);
|
||||
// //Serial.print(" ");
|
||||
// Serial.print(readingPulldown);
|
||||
// Serial.print(readingPulldown2);
|
||||
// Serial.print(readingPulldown3);
|
||||
// Serial.print("\n\r");
|
||||
|
||||
if (readingPullup == 1 && readingPulldown == 0)
|
||||
|
||||
if (readingPullup2 == 1 && readingPulldown2 == 0)
|
||||
{
|
||||
|
||||
state = floating;
|
||||
}
|
||||
else if (readingPullup == 1 && readingPulldown == 1)
|
||||
else if (readingPullup2 == 1 && readingPulldown2 == 1)
|
||||
{
|
||||
// Serial.print(readingPullup);
|
||||
// // Serial.print(readingPullup2);
|
||||
// // Serial.print(readingPullup3);
|
||||
// // //Serial.print(" ");
|
||||
// Serial.print(readingPulldown);
|
||||
// // Serial.print(readingPulldown2);
|
||||
// // Serial.print(readingPulldown3);
|
||||
// Serial.print("\n\r");
|
||||
|
||||
state = high;
|
||||
}
|
||||
else if (readingPullup == 0 && readingPulldown == 0)
|
||||
else if (readingPullup2 == 0 && readingPulldown2 == 0)
|
||||
{
|
||||
|
||||
// Serial.print(readingPullup);
|
||||
// // Serial.print(readingPullup2);
|
||||
// // Serial.print(readingPullup3);
|
||||
// // //Serial.print(" ");
|
||||
// Serial.print(readingPulldown);
|
||||
// // Serial.print(readingPulldown2);
|
||||
// // Serial.print(readingPulldown3);
|
||||
// Serial.print("\n\r");
|
||||
state = low;
|
||||
}
|
||||
else if (readingPullup == 0 && readingPulldown == 1)
|
||||
@ -572,17 +708,17 @@ void startProbe(long probeSpeed)
|
||||
|
||||
probeFrequency = probeSpeed;
|
||||
probeHalfPeriodus = 1000000 / probeSpeed / 2;
|
||||
pinMode(19, OUTPUT);
|
||||
pinMode(probePin, OUTPUT);
|
||||
analogWriteFreq(probeSpeed);
|
||||
analogWrite(19, 128);
|
||||
analogWrite(probePin, 128);
|
||||
// delayMicroseconds(10);
|
||||
// pinMode(18, INPUT);
|
||||
// pinMode(buttonPin, INPUT);
|
||||
}
|
||||
|
||||
void stopProbe()
|
||||
{
|
||||
pinMode(19, INPUT);
|
||||
pinMode(18, INPUT);
|
||||
pinMode(probePin, INPUT);
|
||||
pinMode(buttonPin, INPUT);
|
||||
}
|
||||
|
||||
int checkLastFound(int found)
|
||||
@ -612,9 +748,9 @@ int scanRows(int pin)
|
||||
digitalWrite(RESETPIN, LOW);
|
||||
// delayMicroseconds(20);
|
||||
|
||||
pinMode(19, INPUT);
|
||||
// delayMicroseconds(10);
|
||||
int probeRead = readFloatingOrState(19, -1);
|
||||
pinMode(probePin, INPUT);
|
||||
delayMicroseconds(400);
|
||||
int probeRead = readFloatingOrState(probePin, -1);
|
||||
|
||||
if (probeRead == high)
|
||||
{
|
||||
@ -622,6 +758,8 @@ int scanRows(int pin)
|
||||
connectedRows[connectedRowsIndex] = found;
|
||||
connectedRowsIndex++;
|
||||
// return connectedRows[connectedRowsIndex];
|
||||
//Serial.print("high");
|
||||
return found;
|
||||
}
|
||||
|
||||
else if (probeRead == low)
|
||||
@ -629,6 +767,8 @@ int scanRows(int pin)
|
||||
found = GND;
|
||||
connectedRows[connectedRowsIndex] = found;
|
||||
connectedRowsIndex++;
|
||||
return found;
|
||||
// return connectedRows[connectedRowsIndex];
|
||||
// Serial.print(connectedRows[connectedRowsIndex]);
|
||||
|
||||
// return connectedRows[connectedRowsIndex];
|
||||
@ -785,6 +925,10 @@ int scanRows(int pin)
|
||||
|
||||
// stopProbe();
|
||||
// probeTimeout = millis();
|
||||
|
||||
digitalWrite(RESETPIN, HIGH);
|
||||
delayMicroseconds(20);
|
||||
digitalWrite(RESETPIN, LOW);
|
||||
return connectedRows[0];
|
||||
// return found;
|
||||
|
||||
|
@ -6,6 +6,10 @@
|
||||
|
||||
extern unsigned long probingTimer;
|
||||
extern long probeFrequency;
|
||||
extern int probePin;
|
||||
extern int buttonPin;
|
||||
|
||||
extern int probeSwap;
|
||||
|
||||
enum measuredState
|
||||
{
|
||||
|
@ -131,7 +131,7 @@ int baudRate = 115200;
|
||||
|
||||
int restoredNodeFile = 0;
|
||||
|
||||
const char firmwareVersion[] = "1.3.4"; //// remember to update this
|
||||
const char firmwareVersion[] = "1.3.5"; //// remember to update this
|
||||
|
||||
void loop()
|
||||
{
|
||||
@ -151,14 +151,16 @@ 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("\ts = show node file\n\r");
|
||||
Serial.print("\tf = load formatted node file\n\r");
|
||||
Serial.print("\tw = waveGen\n\r");
|
||||
Serial.print("\tv = toggle show current/voltage\n\r");
|
||||
Serial.print("\tf = load formatted nodeFile\n\r");
|
||||
Serial.print("\tu = set baud rate for USB-Serial\n\r");
|
||||
Serial.print("\tl = LED brightness / test\n\r");
|
||||
Serial.print("\td = toggle debug flags\n\r");
|
||||
Serial.print("\tr = reset Arduino\n\r");
|
||||
Serial.print("\tp = probe connections\n\r");
|
||||
Serial.print("\tc = clear nodes with probe\n\r");
|
||||
Serial.print("\n\n\r");
|
||||
|
||||
dontshowmenu:
|
||||
@ -182,7 +184,7 @@ dontshowmenu:
|
||||
{
|
||||
if (checkProbeButton() == 1)
|
||||
{
|
||||
int longShort = longShortPress(1500);
|
||||
int longShort = longShortPress(1000);
|
||||
if (longShort == 1)
|
||||
{
|
||||
input = 'c';
|
||||
@ -222,6 +224,17 @@ skipinput:
|
||||
Serial.println(firmwareVersion);
|
||||
break;
|
||||
}
|
||||
|
||||
case 's':
|
||||
Serial.print("\n\n\r");
|
||||
Serial.print("\tNode File\n\r");
|
||||
Serial.print("\n\ryou can paste this into the menu to reload this circuit");
|
||||
Serial.print("\n\r(make sure you grab an extra blank line at the end)\n\r");
|
||||
Serial.print("\n\n\rf ");
|
||||
printNodeFile();
|
||||
Serial.print("\n\n\r");
|
||||
break;
|
||||
|
||||
case 'v':
|
||||
|
||||
if (showReadings >= 3 || (inaConnected == 0 && showReadings >= 1))
|
||||
@ -326,6 +339,7 @@ skipinput:
|
||||
savePreformattedNodeFile(serSource);
|
||||
|
||||
// Serial.print("savePFNF\n\r");
|
||||
//debugFP = 1;
|
||||
openNodeFile();
|
||||
getNodesToConnect();
|
||||
// Serial.print("openNF\n\r");
|
||||
@ -440,22 +454,26 @@ skipinput:
|
||||
|
||||
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("\n\r2. net manager = ");
|
||||
Serial.print(debugNM);
|
||||
Serial.print("\n\r4. net manager time = ");
|
||||
Serial.print(debugNMtime);
|
||||
|
||||
Serial.print("\n\r5. chip connections = ");
|
||||
Serial.print("\n\r3. chip connections = ");
|
||||
Serial.print(debugNTCC);
|
||||
Serial.print("\n\r6. chip conns alt paths = ");
|
||||
Serial.print("\n\r4. chip conns alt paths = ");
|
||||
Serial.print(debugNTCC2);
|
||||
Serial.print("\n\r7. LEDs = ");
|
||||
Serial.print("\n\r5. LEDs = ");
|
||||
Serial.print(debugLEDs);
|
||||
Serial.print("\n\n\r6. swap probe pin = ");
|
||||
if (probeSwap == 0)
|
||||
{
|
||||
Serial.print("19");
|
||||
}
|
||||
else
|
||||
{
|
||||
Serial.print("18");
|
||||
}
|
||||
|
||||
Serial.print("\n\n\r");
|
||||
|
||||
Serial.print("\n\n\n\r");
|
||||
|
||||
while (Serial.available() == 0)
|
||||
;
|
||||
@ -742,11 +760,23 @@ void loop1() // core 2 handles the LEDs and the CH446Q8
|
||||
{
|
||||
int rails = showLEDsCore2;
|
||||
|
||||
// showNets();
|
||||
|
||||
|
||||
if (rails == 1)
|
||||
{
|
||||
lightUpRail(-1, -1, 1, 28, supplySwitchPosition);
|
||||
}
|
||||
|
||||
|
||||
if (rails == 2)
|
||||
{
|
||||
|
||||
} else {
|
||||
showNets();
|
||||
}
|
||||
|
||||
|
||||
|
||||
if (rails > 3)
|
||||
{
|
||||
Serial.print("\n\r");
|
||||
@ -844,7 +874,7 @@ void loop1() // core 2 handles the LEDs and the CH446Q8
|
||||
logoFlash = 1;
|
||||
}
|
||||
|
||||
if (logoFlash == 1 && logoFlashTimer != 0 && millis() - logoFlashTimer > 250)
|
||||
if (logoFlash == 1 && logoFlashTimer != 0 && millis() - logoFlashTimer > 150)
|
||||
{
|
||||
logoFlash = 0;
|
||||
logoFlashTimer = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user