Fixed routing for Special Function chips

This commit is contained in:
Kevin Santo Cappuccio 2023-10-28 13:30:25 -07:00
parent be0867c9a5
commit ede51b0219
8 changed files with 240 additions and 86 deletions

BIN
Hardware/.DS_Store vendored

Binary file not shown.

View File

@ -26,3 +26,4 @@ lib_deps =
arduino-libraries/Arduino_JSON@^0.2.0 arduino-libraries/Arduino_JSON@^0.2.0
adafruit/Adafruit NeoPixel@^1.11.0 adafruit/Adafruit NeoPixel@^1.11.0
robtillaart/MCP_DAC@^0.2.0 robtillaart/MCP_DAC@^0.2.0

View File

@ -193,6 +193,9 @@
#define ADC2_5V 112 #define ADC2_5V 112
#define ADC3_8V 113 #define ADC3_8V 113
#define GPIO_0 114
#define UART_TX 115
#define UART_RX 116
#define EMPTY_NET 127 #define EMPTY_NET 127

View File

@ -421,6 +421,7 @@ showLEDsCore2 = 1;
{ {
randomColors(0,90); randomColors(0,90);
} }
delay(10000);
input = '!'; input = '!';
@ -1197,11 +1198,15 @@ void randomColors(uint32_t color, int wait)
for (int i = 0; i < leds.numPixels(); i++) for (int i = 0; i < leds.numPixels(); i++)
{ {
count = random(0,7); count = random(0,8);
if (i > 80)
{
count = random(0,22);
}
byte colorValR = random(0, 0x2f); byte colorValR = random(60, 0x3f);
byte colorValG = random(0, 0x20); byte colorValG = random(60, 0x30);
byte colorValB = random(0, 0x2f); byte colorValB = random(60, 0x3f);
color = colorValR << 16 | colorValG << 8 | colorValB; color = colorValR << 16 | colorValG << 8 | colorValB;
switch (count) switch (count)
@ -1224,16 +1229,22 @@ void randomColors(uint32_t color, int wait)
case 5: case 5:
color = color & 0xff0000; color = color & 0xff0000;
break; break;
default:
color = color & 0x000000;
break;
} }
//color = color | (color >> 1);
leds.setPixelColor(i, color); // Set pixel's color (in RAM) leds.setPixelColor(i, color); // Set pixel's color (in RAM)
lightUpRail(-1,-1,1,LEDbrightnessRail);
showLEDsCore2 = 2; // Update strip to match showLEDsCore2 = 2; // Update strip to match
// Pause for a moment // Pause for a moment
} }
delay(500);
delay(wait); delay(wait);
} }

View File

@ -137,6 +137,7 @@ struct pathStruct{
enum nodeType nodeType[3]; enum nodeType nodeType[3];
bool sameChip; bool sameChip;
bool Lchip; bool Lchip;
bool doubleHop;
}; };

View File

@ -122,7 +122,6 @@ void clearAllNTCC(void)
ch[i].yStatus[j] = -1; ch[i].yStatus[j] = -1;
} }
} }
} }
void sortPathsByNet(void) // not actually sorting, just copying the bridges and nets back from netStruct so they're both in the same order void sortPathsByNet(void) // not actually sorting, just copying the bridges and nets back from netStruct so they're both in the same order
@ -277,6 +276,13 @@ void bridgesToPaths(void)
resolveChipCandidates(); resolveChipCandidates();
commitPaths(); commitPaths();
resolveUncommittedHops(); resolveUncommittedHops();
if (debugNTCC2)
{
delay(10);
printPathsCompact();
printChipStatus();
}
// resolveChipCandidates(); // resolveChipCandidates();
} }
@ -290,7 +296,7 @@ void commitPaths(void)
// Serial.print(i); // Serial.print(i);
// Serial.print(" \t"); // Serial.print(" \t");
if (debugNTCC2 == true) if (debugNTCC == true)
{ {
Serial.print("path["); Serial.print("path[");
Serial.print(i); Serial.print(i);
@ -335,7 +341,7 @@ void commitPaths(void)
path[i].x[0] = -2; path[i].x[0] = -2;
path[i].x[1] = -2; path[i].x[1] = -2;
if (debugNTCC2 == true) if (debugNTCC == true)
{ {
Serial.print(" \tchip[0]: "); Serial.print(" \tchip[0]: ");
@ -427,7 +433,7 @@ void commitPaths(void)
ch[path[i].chip[0]].yStatus[path[i].y[0]] = path[i].net; ch[path[i].chip[0]].yStatus[path[i].y[0]] = path[i].net;
ch[path[i].chip[1]].yStatus[path[i].y[1]] = path[i].net; ch[path[i].chip[1]].yStatus[path[i].y[1]] = path[i].net;
if (debugNTCC2 == true) if (debugNTCC == true)
{ {
Serial.print(" \tchip[0]: "); Serial.print(" \tchip[0]: ");
@ -496,7 +502,7 @@ void commitPaths(void)
// path[i].sameChip = true; //so we know both -2 values need to be the same // path[i].sameChip = true; //so we know both -2 values need to be the same
if (debugNTCC2 == true) if (debugNTCC == true)
{ {
Serial.print(" \tchip[0]: "); Serial.print(" \tchip[0]: ");
@ -529,7 +535,7 @@ void commitPaths(void)
path[i].x[1] = xMapChipL; path[i].x[1] = xMapChipL;
if (debugNTCC2) if (debugNTCC2)
{ {
Serial.print("\tno free lanes for path, setting altPathNeeded flag"); Serial.print("\tno free lanes for path, setting altPathNeeded flag for Chip L");
} }
path[i].altPathNeeded = true; path[i].altPathNeeded = true;
} }
@ -560,6 +566,7 @@ void commitPaths(void)
if (debugNTCC2 == true) if (debugNTCC2 == true)
{ {
//delay(10);
Serial.print(" \tchip[0]: "); Serial.print(" \tchip[0]: ");
Serial.print(chipNumToChar(path[i].chip[0])); Serial.print(chipNumToChar(path[i].chip[0]));
@ -596,6 +603,7 @@ void commitPaths(void)
if (debugNTCC2) if (debugNTCC2)
{ {
//delay(10);
Serial.print("\tno direct path, setting altPathNeeded flag (BBtoSF)"); Serial.print("\tno direct path, setting altPathNeeded flag (BBtoSF)");
} }
break; break;
@ -626,7 +634,7 @@ void commitPaths(void)
path[i].y[1] = -2; path[i].y[1] = -2;
path[i].sameChip = true; path[i].sameChip = true;
if (debugNTCC2) if (false)
{ {
Serial.print(" \tchip[0]: "); Serial.print(" \tchip[0]: ");
@ -667,13 +675,8 @@ void commitPaths(void)
} }
duplicateSFnets(); duplicateSFnets();
resolveAltPaths(); resolveAltPaths();
if (debugNTCC2)
{
printPathsCompact();
printChipStatus(); // duplicateSFnets();
}
duplicateSFnets();
} }
void duplicateSFnets(void) void duplicateSFnets(void)
@ -733,9 +736,9 @@ void resolveAltPaths(void)
if (path[i].Lchip == true) if (path[i].Lchip == true)
{ {
// Serial.print("Lchip"); Serial.print("Lchip");
if (ch[CHIP_L].yStatus[bb] == -1 || ch[CHIP_L].yStatus[bb] == path[1].net) if (ch[CHIP_L].yStatus[bb] == -1 || ch[CHIP_L].yStatus[bb] == path[i].net) /////////
{ {
int xMapL0c0 = xMapForChipLane0(path[i].chip[0], path[i].chip[bb]); int xMapL0c0 = xMapForChipLane0(path[i].chip[0], path[i].chip[bb]);
@ -762,7 +765,8 @@ void resolveAltPaths(void)
{ {
continue; continue;
} }
ch[CHIP_L].yStatus[bb] = path[1].net;
ch[CHIP_L].yStatus[bb] = path[i].net; //////
path[i].chip[2] = bb; path[i].chip[2] = bb;
path[i].altPathNeeded = false; path[i].altPathNeeded = false;
@ -910,12 +914,9 @@ void resolveAltPaths(void)
continue; continue;
} }
if (ch[sfChip].yStatus[yMapSF] != -1 && ch[sfChip].yStatus[yMapSF] != path[i].net) if (ch[sfChip].yStatus[yMapSF] != -1 && ch[sfChip].yStatus[yMapSF] != path[i].net)
{ {
continue; continue;
} }
path[i].chip[2] = bb; path[i].chip[2] = bb;
@ -1423,25 +1424,155 @@ void resolveAltPaths(void)
int giveUpOnL = 0; int giveUpOnL = 0;
int swapped = 0; int swapped = 0;
if (path[i].Lchip == true) if (path[i].Lchip == true)
{
int sfChip1 = path[i].chip[0];
int sfChip2 = path[i].chip[1];
if (((sfChip1 == CHIP_L && sfChip2 >= CHIP_I) || (sfChip2 == CHIP_L && sfChip1 >= CHIP_I)) && sfChip1 != sfChip2)
{
if (debugNTCC2)
{
Serial.println("L to Special Function via ADCs");
}
int whichIsL = 0;
int whichIsSF = 1;
if (sfChip1 == CHIP_L)
{
whichIsL = 0;
whichIsSF = 1;
}
else
{
whichIsL = 1;
whichIsSF = 0;
}
//Serial.println(whichIsL);
int whichADC = path[i].chip[whichIsSF] - CHIP_I;
if (debugNTCC2)
{
Serial.println(whichADC);
Serial.println("sfChip1: ");
Serial.println(sfChip1);
Serial.println("sfChip2: ");
Serial.println(sfChip2);
}
path[i].x[whichIsL] = whichADC + 2;
path[i].y[whichIsL] = -2;
if (whichIsSF == 0)
{
path[i].x[whichIsSF] = xMapForNode(ADC0_5V + whichADC, sfChip1);
} else {
path[i].x[whichIsSF] = xMapForNode(ADC0_5V + whichADC, sfChip2);
}
if (debugNTCC2)
{
Serial.println(path[i].x[whichIsSF]);
Serial.print("path[i].node1; ");
Serial.println(path[i].node1);
Serial.print("path[i].node2; ");
Serial.println(path[i].node2);
Serial.print("xMapForNode(path[i].node1, sfChip1); ");
Serial.println(xMapForNode(path[i].node1, sfChip1));
Serial.print("xMapForNode(path[i].node2, sfChip2); ");
Serial.println(xMapForNode(path[i].node2, sfChip2));
}
path[i].y[whichIsSF] = -2;
if (whichIsL == 0)
{
path[i].x[3] = xMapForNode(path[i].node1, sfChip2);
path[i].x[2] = xMapForNode(path[i].node2, sfChip1);
path[i].chip[3] = sfChip1;
path[i].chip[2] = sfChip2;
path[i].y[2] = -2;
path[i].y[3] = -2;
ch[sfChip1].xStatus[path[i].x[whichIsL]] = path[i].net;
ch[sfChip1].xStatus[whichADC + 2] = path[i].net;
ch[sfChip2].xStatus[path[i].x[whichIsSF]] = path[i].net;
ch[sfChip2].xStatus[xMapForNode(path[i].node2, sfChip2)] = path[i].net;
ch[sfChip1].xStatus[xMapForNode(path[i].node1, sfChip1)] = path[i].net;
}
else
{
path[i].chip[3] = sfChip1;
path[i].chip[2] = sfChip2;
path[i].x[3] = xMapForNode(path[i].node1, sfChip1);
path[i].x[2] = xMapForNode(path[i].node2, sfChip2);
path[i].y[2] = -2;
path[i].y[3] = -2;
ch[sfChip1].xStatus[path[i].x[whichIsSF]] = path[i].net;
ch[sfChip1].xStatus[xMapForNode(path[i].node1, sfChip1)] = path[i].net;
ch[sfChip2].xStatus[xMapForNode(path[i].node2, sfChip2)] = path[i].net;
ch[sfChip2].xStatus[path[i].x[whichIsL]] = path[i].net;
ch[sfChip2].xStatus[whichADC + 2] = path[i].net;
}
path[i].altPathNeeded = false;
//path[i].sameChip = true;
//resolveUncommittedHops();
for (int ySearch = 0; ySearch < 8; ySearch++)
{
if (ch[sfChip1].yStatus[ySearch] == path[i].net || ch[sfChip1].yStatus[ySearch] == -1)
{
ch[sfChip1].yStatus[ySearch] = path[i].net;
path[i].y[whichIsL] = ySearch;
path[i].y[whichIsL+2] = ySearch;
break;
}
}
for (int ySearch = 0; ySearch < 8; ySearch++)
{
if (ch[sfChip2].yStatus[ySearch] == path[i].net || ch[sfChip2].yStatus[ySearch] == -1)
{
ch[sfChip2].yStatus[ySearch] = path[i].net;
path[i].y[whichIsSF] = ySearch;
path[i].y[whichIsSF+2] = ySearch;
break;
}
}
}
else
{ {
for (int bb = 0; bb < 8; bb++) // this is a long winded way to do this but it's at least slightly readable for (int bb = 0; bb < 8; bb++) // this is a long winded way to do this but it's at least slightly readable
{ {
// Serial.print("! "); //Serial.println(bb);
int sfChip1 = path[i].chip[0];
int sfChip2 = path[i].chip[1]; // Serial.print("ERROR: ");
if (sfChip1 == CHIP_L && sfChip2 == CHIP_L) if (sfChip1 == CHIP_L && sfChip2 == CHIP_L)
{ {
path[i].altPathNeeded = false; path[i].altPathNeeded = false;
path[i].x[0] = xMapForNode(path[i].node1, path[i].chip[0]); path[i].x[0] = xMapForNode(path[i].node1, path[i].chip[0]);
path[i].x[1] = xMapForNode(path[i].node2, path[i].chip[1]); path[i].x[1] = xMapForNode(path[i].node2, path[i].chip[1]);
path[i].y[0] = -2; path[i].y[0] = -2;
path[i].y[1] = -2; path[i].y[1] = -2;
// ch[CHIP_L].xStatus[path[i].x[0]] = path[i].net; ch[CHIP_L].xStatus[path[i].x[0]] = path[i].net;
// ch[CHIP_L].xStatus[path[i].x[1]] = path[i].net; ch[CHIP_L].xStatus[path[i].x[1]] = path[i].net;
} }
int chip1Lane = xMapForNode(sfChip1, bb); int chip1Lane = xMapForNode(sfChip1, bb);
@ -1478,6 +1609,7 @@ void resolveAltPaths(void)
} }
} }
} }
}
else else
{ {
for (int bb = 0; bb < 8; bb++) // this is a long winded way to do this but it's at least slightly readable for (int bb = 0; bb < 8; bb++) // this is a long winded way to do this but it's at least slightly readable
@ -1790,7 +1922,6 @@ void resolveUncommittedHops(void)
if (ch[thisChip].xStatus[freeXSearchOrder[thisChip][freeXidx]] == -1 && freeXSearchOrder[thisChip][freeXidx] != -1) if (ch[thisChip].xStatus[freeXSearchOrder[thisChip][freeXidx]] == -1 && freeXSearchOrder[thisChip][freeXidx] != -1)
{ {
otherChip = ch[thisChip].xMap[freeXSearchOrder[thisChip][freeXidx]]; otherChip = ch[thisChip].xMap[freeXSearchOrder[thisChip][freeXidx]];
// otherChipX = ch[otherChip].xMap[checkOtherEnd]; // otherChipX = ch[otherChip].xMap[checkOtherEnd];
@ -1806,17 +1937,15 @@ void resolveUncommittedHops(void)
lane = 1; lane = 1;
} }
if (lane == 1) if (lane == 1)
{ {
otherChipX = xMapForChipLane1(otherChip, thisChip); otherChipX = xMapForChipLane1(otherChip, thisChip);
}
} else if (lane == 0) else if (lane == 0)
{ {
otherChipX = xMapForChipLane0(otherChip, thisChip); otherChipX = xMapForChipLane0(otherChip, thisChip);
} }
// for (int otherChipXidx = 0; otherChipXidx < 16; otherChipXidx++) // for (int otherChipXidx = 0; otherChipXidx < 16; otherChipXidx++)
// { // {
// if (ch[otherChip].xMap[otherChipXidx] == thisChip) // if (ch[otherChip].xMap[otherChipXidx] == thisChip)
@ -1826,7 +1955,6 @@ void resolveUncommittedHops(void)
// } // }
// } // }
otherChipXStatus = ch[otherChip].xStatus[otherChipX]; otherChipXStatus = ch[otherChip].xStatus[otherChipX];
if (debugNTCC2) if (debugNTCC2)
@ -1838,7 +1966,6 @@ void resolveUncommittedHops(void)
Serial.print("thisChipX: "); Serial.print("thisChipX: ");
Serial.println(freeXSearchOrder[thisChip][freeXidx]); Serial.println(freeXSearchOrder[thisChip][freeXidx]);
Serial.print("\nlane: "); Serial.print("\nlane: ");
Serial.println(lane); Serial.println(lane);
Serial.print("otherChip: "); Serial.print("otherChip: ");
@ -1872,7 +1999,7 @@ void resolveUncommittedHops(void)
} }
if (debugNTCC2) if (debugNTCC2)
{ {
printChipStatus(); //printChipStatus();
} }
} }
} }
@ -1885,8 +2012,13 @@ void resolveUncommittedHops(void)
if (sameChips[1][chip] != -1) if (sameChips[1][chip] != -1)
{ {
for (int freeYsearch = 0; freeYsearch < 8; freeYsearch++) for (int freeYsearch = 0; freeYsearch < 8; freeYsearch++) ////////// make it search l chip connections first
{ {
// Serial.print("freeYsearch: ");
// Serial.print(freeYsearch);
// Serial.print(" status: ");
// Serial.print(ch[sameChips[1][chip]].yStatus[freeYsearch]);
// Serial.println(" ");
if (ch[sameChips[1][chip]].yStatus[freeYsearch] == -1) if (ch[sameChips[1][chip]].yStatus[freeYsearch] == -1)
{ {
@ -1926,7 +2058,7 @@ void resolveUncommittedHops(void)
if (debugNTCC2) if (debugNTCC2)
{ {
printPathsCompact(); // printPathsCompact();
} }
} }
@ -2358,7 +2490,7 @@ void assignPathType(int pathIndex)
} }
else if ((path[pathIndex].nodeType[0] == SF && path[pathIndex].nodeType[1] == SF)) else if ((path[pathIndex].nodeType[0] == SF && path[pathIndex].nodeType[1] == SF))
{ {
path[pathIndex].pathType = NANOtoSF; path[pathIndex].pathType = NANOtoSF; // SFtoSF is dealt with the same as NANOtoSF
} }
else if ((path[pathIndex].nodeType[0] == SF && path[pathIndex].nodeType[1] == NANO)) else if ((path[pathIndex].nodeType[0] == SF && path[pathIndex].nodeType[1] == NANO))
{ {

View File

@ -79,6 +79,7 @@ void initDAC(void)
{ {
Wire.begin(); Wire.begin();
delay(5);
if (dac1_8V.begin(MCP4725A1_Addr_A01, i2c0, 400, 4, 5) == true) if (dac1_8V.begin(MCP4725A1_Addr_A01, i2c0, 400, 4, 5) == true)
{ {
revisionNumber = 2; revisionNumber = 2;

View File

@ -127,8 +127,13 @@ menu:
listNets(); listNets();
break; break;
case 'b': case 'b':
Serial.print("\n\n\rBridge Array\n\r");
printBridgeArray(); printBridgeArray();
Serial.print("\n\n\n\rPaths\n\r");
printPathsCompact();
Serial.print("\n\n\rChip Status\n\r");
printChipStatus();
Serial.print("\n\n\r");
break; break;
case 'm': case 'm':