mirror of
https://github.com/Architeuthis-Flux/Jumperless.git
synced 2024-11-23 23:00:57 +01:00
Added Voltage/Current sensing interface
toggle it on with 'v' in the main menu. You'll need the new Wokwi bridge app to connect the current sensor lines
This commit is contained in:
parent
fb41f849f8
commit
df7991df8e
BIN
Hardware/.DS_Store
vendored
BIN
Hardware/.DS_Store
vendored
Binary file not shown.
BIN
Hardware/KiCAD/.DS_Store
vendored
BIN
Hardware/KiCAD/.DS_Store
vendored
Binary file not shown.
@ -628,9 +628,12 @@ while True:
|
||||
|
||||
print("\n\n\rsketch.ino\n\r")
|
||||
print(sketch)
|
||||
|
||||
print("\n\n\rlibraries.txt\n\r")
|
||||
print(libraries)
|
||||
|
||||
try:
|
||||
print("\n\n\rlibraries.txt\n\r")
|
||||
print(libraries)
|
||||
except:
|
||||
print("\n\n\rNo libraries.txt\n\r")
|
||||
|
||||
# if (justreconnected == 1):
|
||||
|
||||
@ -662,6 +665,10 @@ while True:
|
||||
conn1 = "112"
|
||||
elif conn1.endswith('3'):
|
||||
conn1 = "113"
|
||||
elif conn1.endswith('4'):
|
||||
conn1 = "108"
|
||||
elif conn1.endswith('5'):
|
||||
conn1 = "109"
|
||||
|
||||
if conn1.startswith("bb1:") == True:
|
||||
periodIndex = conn1.find('.')
|
||||
@ -727,6 +734,10 @@ while True:
|
||||
conn2 = "112"
|
||||
elif conn2.endswith('3'):
|
||||
conn2 = "113"
|
||||
elif conn2.endswith('4'):
|
||||
conn2 = "108"
|
||||
elif conn2.endswith('5'):
|
||||
conn2 = "109"
|
||||
|
||||
if conn2.startswith("bb1:") == True:
|
||||
periodIndex = conn2.find('.')
|
||||
|
@ -2,4 +2,5 @@ fuck https://wokwi.com/projects/369614891595393025
|
||||
fuck2 https://wokwi.com/projects/367384677537829889
|
||||
fuck3 https://wokwi.com/projects/369024970682423297
|
||||
LEDarray https://wokwi.com/projects/370450364106546177
|
||||
current https://wokwi.com/projects/374273521728204801
|
||||
|
@ -14,7 +14,7 @@
|
||||
|
||||
//SerialPIO ardSerial(1, 0);
|
||||
|
||||
void initArduino (void)
|
||||
void initArduino (void) //if the UART is set up, the Arduino won't flash from it's own USB port
|
||||
{
|
||||
|
||||
//Serial1.setRX(1);
|
||||
|
@ -237,7 +237,10 @@ void sendPath(int i, int setOrClear)
|
||||
|
||||
if (path[i].y[chip] == -1 || path[i].x[chip] == -1)
|
||||
{
|
||||
// Serial.print("!");
|
||||
if (debugNTCC)
|
||||
Serial.print("!");
|
||||
|
||||
|
||||
continue;
|
||||
}
|
||||
|
||||
|
@ -660,6 +660,24 @@ void parseStringToBridges(void)
|
||||
void debugFlagInit(void)
|
||||
{
|
||||
|
||||
if (EEPROM.read(FIRSTSTARTUPADDRESS) == 255)
|
||||
{
|
||||
EEPROM.write(FIRSTSTARTUPADDRESS, 0);
|
||||
EEPROM.write(DEBUG_FILEPARSINGADDRESS, 0);
|
||||
EEPROM.write(TIME_FILEPARSINGADDRESS, 0);
|
||||
EEPROM.write(DEBUG_NETMANAGERADDRESS, 0);
|
||||
EEPROM.write(TIME_NETMANAGERADDRESS, 0);
|
||||
EEPROM.write(DEBUG_NETTOCHIPCONNECTIONSADDRESS, 0);
|
||||
EEPROM.write(DEBUG_NETTOCHIPCONNECTIONSALTADDRESS, 0);
|
||||
EEPROM.write(DEBUG_LEDSADDRESS, 0);
|
||||
EEPROM.write(LEDBRIGHTNESSADDRESS, DEFAULTBRIGHTNESS);
|
||||
EEPROM.write(RAILBRIGHTNESSADDRESS, DEFAULTRAILBRIGHTNESS);
|
||||
EEPROM.write(SPECIALBRIGHTNESSADDRESS, DEFAULTSPECIALNETBRIGHTNESS);
|
||||
|
||||
EEPROM.commit();
|
||||
delay(5);
|
||||
}
|
||||
|
||||
#ifdef EEPROMSTUFF
|
||||
debugFP = EEPROM.read(DEBUG_FILEPARSINGADDRESS);
|
||||
debugFPtime = EEPROM.read(TIME_FILEPARSINGADDRESS);
|
||||
@ -741,18 +759,18 @@ void debugFlagSet(int flag)
|
||||
case 1:
|
||||
{
|
||||
flagStatus = EEPROM.read(DEBUG_FILEPARSINGADDRESS);
|
||||
if (flagStatus == 1)
|
||||
{
|
||||
EEPROM.write(DEBUG_FILEPARSINGADDRESS, 0);
|
||||
|
||||
debugFP = false;
|
||||
}
|
||||
else
|
||||
if (flagStatus == 0)
|
||||
{
|
||||
EEPROM.write(DEBUG_FILEPARSINGADDRESS, 1);
|
||||
|
||||
debugFP = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
EEPROM.write(DEBUG_FILEPARSINGADDRESS, 0);
|
||||
|
||||
debugFP = false;
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
@ -760,18 +778,18 @@ void debugFlagSet(int flag)
|
||||
{
|
||||
flagStatus = EEPROM.read(TIME_FILEPARSINGADDRESS);
|
||||
|
||||
if (flagStatus == 1)
|
||||
{
|
||||
EEPROM.write(TIME_FILEPARSINGADDRESS, 0);
|
||||
|
||||
debugFPtime = false;
|
||||
}
|
||||
else
|
||||
if (flagStatus == 0)
|
||||
{
|
||||
EEPROM.write(TIME_FILEPARSINGADDRESS, 1);
|
||||
|
||||
debugFPtime = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
EEPROM.write(TIME_FILEPARSINGADDRESS, 0);
|
||||
|
||||
debugFPtime = false;
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
@ -779,72 +797,73 @@ void debugFlagSet(int flag)
|
||||
{
|
||||
flagStatus = EEPROM.read(DEBUG_NETMANAGERADDRESS);
|
||||
|
||||
if (flagStatus == 1)
|
||||
{
|
||||
EEPROM.write(DEBUG_NETMANAGERADDRESS, 0);
|
||||
|
||||
debugNM = false;
|
||||
}
|
||||
else
|
||||
if (flagStatus == 0)
|
||||
{
|
||||
EEPROM.write(DEBUG_NETMANAGERADDRESS, 1);
|
||||
|
||||
debugNM = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
EEPROM.write(DEBUG_NETMANAGERADDRESS, 0);
|
||||
|
||||
debugNM = false;
|
||||
}
|
||||
break;
|
||||
}
|
||||
case 4:
|
||||
{
|
||||
flagStatus = EEPROM.read(TIME_NETMANAGERADDRESS);
|
||||
|
||||
if (flagStatus == 1)
|
||||
{
|
||||
EEPROM.write(TIME_NETMANAGERADDRESS, 0);
|
||||
|
||||
debugNMtime = false;
|
||||
}
|
||||
else
|
||||
if (flagStatus == 0)
|
||||
{
|
||||
EEPROM.write(TIME_NETMANAGERADDRESS, 1);
|
||||
|
||||
debugNMtime = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
EEPROM.write(TIME_NETMANAGERADDRESS, 0);
|
||||
|
||||
debugNMtime = false;
|
||||
}
|
||||
break;
|
||||
}
|
||||
case 5:
|
||||
{
|
||||
flagStatus = EEPROM.read(DEBUG_NETTOCHIPCONNECTIONSADDRESS);
|
||||
|
||||
if (flagStatus == 1)
|
||||
{
|
||||
EEPROM.write(DEBUG_NETTOCHIPCONNECTIONSADDRESS, 0);
|
||||
|
||||
debugNTCC = false;
|
||||
}
|
||||
else
|
||||
if (flagStatus == 0)
|
||||
{
|
||||
EEPROM.write(DEBUG_NETTOCHIPCONNECTIONSADDRESS, 1);
|
||||
|
||||
debugNTCC = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
EEPROM.write(DEBUG_NETTOCHIPCONNECTIONSADDRESS, 0);
|
||||
|
||||
debugNTCC = false;
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
case 6:
|
||||
{
|
||||
flagStatus = EEPROM.read(DEBUG_NETTOCHIPCONNECTIONSALTADDRESS);
|
||||
if (flagStatus == 1)
|
||||
{
|
||||
EEPROM.write(DEBUG_NETTOCHIPCONNECTIONSALTADDRESS, 0);
|
||||
|
||||
debugNTCC2 = false;
|
||||
}
|
||||
else
|
||||
if (flagStatus == 0)
|
||||
{
|
||||
EEPROM.write(DEBUG_NETTOCHIPCONNECTIONSALTADDRESS, 1);
|
||||
|
||||
debugNTCC2 = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
EEPROM.write(DEBUG_NETTOCHIPCONNECTIONSALTADDRESS, 0);
|
||||
|
||||
debugNTCC2 = false;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
@ -852,18 +871,18 @@ void debugFlagSet(int flag)
|
||||
{
|
||||
flagStatus = EEPROM.read(DEBUG_LEDSADDRESS);
|
||||
|
||||
if (flagStatus == 1)
|
||||
{
|
||||
EEPROM.write(DEBUG_LEDSADDRESS, 0);
|
||||
|
||||
debugLEDs = false;
|
||||
}
|
||||
else
|
||||
if (flagStatus == 0)
|
||||
{
|
||||
EEPROM.write(DEBUG_LEDSADDRESS, 1);
|
||||
|
||||
debugLEDs = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
EEPROM.write(DEBUG_LEDSADDRESS, 0);
|
||||
|
||||
debugLEDs = false;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
|
@ -15,6 +15,8 @@
|
||||
#define RAILBRIGHTNESSADDRESS 40
|
||||
#define SPECIALBRIGHTNESSADDRESS 41
|
||||
|
||||
#define FIRSTSTARTUPADDRESS 42
|
||||
|
||||
|
||||
|
||||
|
||||
|
@ -113,7 +113,7 @@ struct chipStatus ch[12] = {
|
||||
{11,'L',
|
||||
{-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1}, // x status
|
||||
{-1,-1,-1,-1,-1,-1,-1,-1}, //y status
|
||||
{CURRENT_SENSE_MINUS, CURRENT_SENSE_PLUS, ADC0_5V, ADC1_5V, ADC2_5V, ADC3_8V, DAC1_8V, DAC0_5V, t1, t30, b1, b30, NANO_A4, NANO_A5, SUPPLY_5V, RP_GPIO_0},
|
||||
{CURRENT_SENSE_MINUS, CURRENT_SENSE_PLUS, ADC0_5V, ADC1_5V, ADC2_5V, ADC3_8V, DAC1_8V, DAC0_5V, t1, t30, b1, b30, RP_UART_RX, RP_UART_TX, SUPPLY_5V, RP_GPIO_0},
|
||||
{CHIP_A,CHIP_B,CHIP_C,CHIP_D,CHIP_E,CHIP_F,CHIP_G,CHIP_H}}
|
||||
};
|
||||
|
||||
@ -132,7 +132,7 @@ struct nanoStatus nano = { //there's only one of these so ill declare and inita
|
||||
{ 1 , 1 , 2 , 2 , 2 , 2 , 2 , 2 , 2 , 2 , 2 , 2 , 2 , 1 , 1 , 1 , 2 , 2 , 2 , 2 , 2 , 2 , 1 , 1 },//Whether this pin has 1 or 2 connections to special function chips (OR maybe have it be a map like i = 2 j = 3 k = 4 l = 5 if there's 2 it's the product of them ij = 6 ik = 8 il = 10 jk = 12 jl = 15 kl = 20 we're trading minuscule amounts of CPU for RAM)
|
||||
// | | | | | | | | | | | | | | | | | | | | | | | | |
|
||||
{ CHIP_J , CHIP_I , CHIP_J , CHIP_I , CHIP_J , CHIP_I , CHIP_J , CHIP_I , CHIP_J , CHIP_I , CHIP_J , CHIP_I , CHIP_J , CHIP_I , CHIP_I , CHIP_J , CHIP_I , CHIP_J , CHIP_I , CHIP_J , CHIP_I , CHIP_J , CHIP_I , CHIP_J },//Since there's no overlapping connections between Chip I and J, this holds which of those 2 chips has a connection at that index, if numConns is 1, you only need to check this one
|
||||
{ -1 , -1 , CHIP_K , CHIP_K , CHIP_K , CHIP_K , CHIP_K , CHIP_K , CHIP_K , CHIP_K , CHIP_K , CHIP_K , CHIP_K , -1 , -1 , -1 , CHIP_K , CHIP_K , CHIP_K , CHIP_K , CHIP_L , CHIP_L , -1 , -1 },//Since there's no overlapping connections between Chip K and L, this holds which of those 2 chips has a connection at that index, -1 for no connection
|
||||
{ -1 , -1 , CHIP_K , CHIP_K , CHIP_K , CHIP_K , CHIP_K , CHIP_K , CHIP_K , CHIP_K , CHIP_K , CHIP_K , CHIP_K , -1 , -1 , -1 , CHIP_K , CHIP_K , CHIP_K , CHIP_K , -1 , -1 , -1 , -1 },//Since there's no overlapping connections between Chip K and L, this holds which of those 2 chips has a connection at that index, -1 for no connection
|
||||
// | | | | | | | | | | | | | | | | | | | | | | | | |
|
||||
{ -1 , 1 , -1 , 3 , -1 , 5 , -1 , 7 , -1 , 9 , -1 , 8 , -1 , 10 , 11 , -1 , 0 , -1 , 2 , -1 , 4 , -1 , 6 , -1 },//holds which X pin is connected to the index on Chip I, -1 for none
|
||||
{ -1 , 0 , -1 , 0 , -1 , 0 , -1 , 0 , -1 , 0 , -1 , 0 , -1 , 0 , 0 , -1 , 0 , -1 , 0 , -1 , 0 , -1 , 0 , -1 },//-1 for not connected to that chip, 0 for available, >0 means it's connected and the netNumber is stored here
|
||||
|
@ -473,7 +473,7 @@ void commitPaths(void)
|
||||
|
||||
if (path[i].chip[0] != CHIP_L && path[i].chip[1] == CHIP_L) // if theyre both chip L we'll deal with it differently
|
||||
{
|
||||
// Serial.print("\tBBtoCHIP L ");
|
||||
// Serial.print("\tBBtoCHIP L \n\n\n\n");
|
||||
int yMapBBc0 = 0; // y 0 is always connected to chip L
|
||||
|
||||
int xMapChipL = xMapForNode(path[i].node2, CHIP_L);
|
||||
@ -1151,6 +1151,7 @@ void resolveAltPaths(void)
|
||||
|
||||
if (foundPath == 1)
|
||||
{
|
||||
|
||||
break;
|
||||
}
|
||||
int giveUpOnL = 0;
|
||||
@ -2487,7 +2488,7 @@ void assignPathType(int pathIndex)
|
||||
if ((path[pathIndex].node1 == 1 || path[pathIndex].node1 == 30 || path[pathIndex].node1 == 31 || path[pathIndex].node1 == 60) || path[pathIndex].chip[0] == CHIP_L)
|
||||
{
|
||||
// Serial.print("\n\n\rthis should be a bb to sf connection\n\n\n\r ");
|
||||
path[pathIndex].altPathNeeded = true;
|
||||
//path[pathIndex].altPathNeeded = true;
|
||||
swapNodes(pathIndex);
|
||||
path[pathIndex].Lchip = true;
|
||||
|
||||
@ -2510,7 +2511,7 @@ void assignPathType(int pathIndex)
|
||||
if ((path[pathIndex].node2 == 1 || path[pathIndex].node2 == 30 || path[pathIndex].node2 == 31 || path[pathIndex].node2 == 60) || path[pathIndex].chip[1] == CHIP_L)
|
||||
{
|
||||
// Serial.print("\n\n\rthis should be a bb to sf connection 2\n\n\n\r ");
|
||||
path[pathIndex].altPathNeeded = true;
|
||||
//path[pathIndex].altPathNeeded = true;
|
||||
path[pathIndex].Lchip = true;
|
||||
path[pathIndex].nodeType[1] = SF;
|
||||
}
|
||||
|
@ -5,7 +5,7 @@
|
||||
#include "Adafruit_INA219.h"
|
||||
|
||||
#include "NetManager.h"
|
||||
|
||||
#include "MatrixStateRP2040.h"
|
||||
#include "LEDs.h"
|
||||
|
||||
#include <Arduino.h>
|
||||
@ -21,10 +21,24 @@
|
||||
|
||||
#include <SPI.h>
|
||||
|
||||
#define CSI Serial.write("\x1B\x5B");
|
||||
|
||||
#define DAC_RESOLUTION 9
|
||||
|
||||
int revisionNumber = 0;
|
||||
|
||||
int showReadings = 0;
|
||||
|
||||
int showADCreadings[4] = {1,1,1,1};
|
||||
|
||||
int showINA0[3] = {1,1,1}; //0 = current, 1 = voltage, 2 = power
|
||||
int showINA1[3] = {0, 0, 0}; //0 = current, 1 = voltage, 2 = power
|
||||
|
||||
|
||||
int showDAC0 = 0;
|
||||
int showDAC1 = 0;
|
||||
|
||||
|
||||
float freq[3] = {1, 1, 0};
|
||||
uint32_t period[3] = {0, 0, 0};
|
||||
uint32_t halvePeriod[3] = {0, 0, 0};
|
||||
@ -147,8 +161,8 @@ void initINA219(void)
|
||||
Serial.println("Failed to find INA219 chip");
|
||||
}
|
||||
|
||||
INA0.setMaxCurrentShunt(1, 2);
|
||||
INA1.setMaxCurrentShunt(1, 2);
|
||||
INA0.setMaxCurrentShunt(1, 2.0);
|
||||
INA1.setMaxCurrentShunt(1, 2.0);
|
||||
|
||||
Serial.println(INA0.setBusVoltageRange(16));
|
||||
Serial.println(INA1.setBusVoltageRange(16));
|
||||
@ -266,20 +280,208 @@ void setDac1_8VinputCode(uint16_t inputCode)
|
||||
}
|
||||
}
|
||||
|
||||
void chooseShownReadings(void)
|
||||
{
|
||||
showADCreadings[0] = 0;
|
||||
showADCreadings[1] = 0;
|
||||
showADCreadings[2] = 0;
|
||||
showADCreadings[3] = 0;
|
||||
|
||||
|
||||
|
||||
|
||||
for (int i = 0; i <= newBridgeIndex; i++)
|
||||
{
|
||||
|
||||
if (path[i].node1 == ADC0_5V || path[i].node2 == ADC0_5V)
|
||||
{
|
||||
showADCreadings[0] = 1;
|
||||
}
|
||||
|
||||
if (path[i].node1 == ADC1_5V || path[i].node2 == ADC1_5V)
|
||||
{
|
||||
showADCreadings[1] = 1;
|
||||
}
|
||||
|
||||
if (path[i].node1 == ADC2_5V || path[i].node2 == ADC2_5V)
|
||||
{
|
||||
showADCreadings[2] = 1;
|
||||
}
|
||||
|
||||
if (path[i].node1 == ADC3_8V || path[i].node2 == ADC3_8V)
|
||||
{
|
||||
showADCreadings[3] = 1;
|
||||
}
|
||||
|
||||
if (path[i].node1 == CURRENT_SENSE_PLUS || path[i].node1 == CURRENT_SENSE_PLUS || path[i].node2 == CURRENT_SENSE_MINUS || path[i].node2 == CURRENT_SENSE_MINUS)
|
||||
{
|
||||
|
||||
switch (showReadings)
|
||||
{
|
||||
case 0:
|
||||
|
||||
case 1:
|
||||
showINA0[0] = 1;
|
||||
showINA0[1] = 0;
|
||||
showINA0[2] = 0;
|
||||
break;
|
||||
case 2:
|
||||
showINA0[0] = 1;
|
||||
showINA0[1] = 1;
|
||||
showINA0[2] = 0;
|
||||
break;
|
||||
case 3:
|
||||
|
||||
showINA0[0] = 1;
|
||||
showINA0[1] = 1;
|
||||
showINA0[2] = 1;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void showMeasurements(int samples)
|
||||
{
|
||||
|
||||
|
||||
while (Serial.available() == 0)
|
||||
{
|
||||
CSI
|
||||
Serial.write("2K");
|
||||
int adc0ReadingUnscaled;
|
||||
float adc0Reading;
|
||||
|
||||
int adc1ReadingUnscaled;
|
||||
float adc1Reading;
|
||||
|
||||
int adc2ReadingUnscaled;
|
||||
float adc2Reading;
|
||||
|
||||
int adc3ReadingUnscaled;
|
||||
float adc3Reading;
|
||||
int bs = 0;
|
||||
|
||||
|
||||
if (showADCreadings[0] == 1)
|
||||
{
|
||||
|
||||
adc0ReadingUnscaled = readAdc(0, samples);
|
||||
adc0Reading = (adc0ReadingUnscaled) * (5.0 / 4095);
|
||||
//adc0Reading -= 0.1; // offset
|
||||
bs+= Serial.print("D0: ");
|
||||
bs+=Serial.print(adc0Reading);
|
||||
bs+=Serial.print("V\t");
|
||||
}
|
||||
|
||||
if (showADCreadings[1] == 1)
|
||||
{
|
||||
|
||||
adc1ReadingUnscaled = readAdc(1, samples);
|
||||
adc1Reading = (adc1ReadingUnscaled) * (5.0 / 4095);
|
||||
//adc1Reading -= 0.1; // offset
|
||||
bs+=Serial.print("D1: ");
|
||||
bs+=Serial.print(adc1Reading);
|
||||
bs+=Serial.print("V\t");
|
||||
}
|
||||
|
||||
if (showADCreadings[2] == 1)
|
||||
{
|
||||
|
||||
adc2ReadingUnscaled = readAdc(2, samples);
|
||||
adc2Reading = (adc2ReadingUnscaled) * (5.0 / 4095);
|
||||
//adc2Reading -= 0.1; // offset
|
||||
|
||||
bs+=Serial.print("D2: ");
|
||||
bs+=Serial.print(adc2Reading);
|
||||
bs+=Serial.print("V\t");
|
||||
}
|
||||
|
||||
if (showADCreadings[3] == 1)
|
||||
{
|
||||
|
||||
adc3ReadingUnscaled = readAdc(3, samples);
|
||||
adc3Reading = (adc3ReadingUnscaled) * (16.0 / 4010);
|
||||
adc3Reading -= 8.7; // offset
|
||||
bs+=Serial.print("D3: ");
|
||||
bs+=Serial.print(adc3Reading);
|
||||
bs+=Serial.print("V\t");
|
||||
}
|
||||
|
||||
if (showINA0[0] == 1 || showINA0[1] == 1 || showINA0[2] == 1)
|
||||
{
|
||||
bs+=Serial.print(" INA219: ");
|
||||
}
|
||||
|
||||
if (showINA0[0] == 1)
|
||||
{
|
||||
bs+=Serial.print("I: ");
|
||||
bs+=Serial.print(INA0.getCurrent_mA());
|
||||
bs+=Serial.print("mA\t");
|
||||
}
|
||||
if (showINA0[1] == 1)
|
||||
{
|
||||
bs+=Serial.print(" V: ");
|
||||
bs+=Serial.print(INA0.getBusVoltage());
|
||||
bs+=Serial.print("V\t");
|
||||
}
|
||||
if (showINA0[2] == 1)
|
||||
{
|
||||
bs+=Serial.print("P: ");
|
||||
bs+=Serial.print(INA0.getPower_mW());
|
||||
bs+=Serial.print("mW\t");
|
||||
}
|
||||
|
||||
bs+=Serial.print(" \r");
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
// for (int i = 0; i < bs; i++)
|
||||
// {
|
||||
// Serial.print("\b");
|
||||
// }
|
||||
|
||||
// Serial.print("ADC1: ");
|
||||
// Serial.print(adc1ReadingUnscaled);
|
||||
// Serial.print("V\n\r");
|
||||
// Serial.print("ADC2: ");
|
||||
// Serial.print(adc2ReadingUnscaled);
|
||||
// Serial.print("V\n\r");
|
||||
// Serial.print("ADC3: ");
|
||||
// Serial.print(adc3ReadingUnscaled);
|
||||
// Serial.print("V\n\n\r");
|
||||
delay(250);
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
int readAdc(int channel, int samples)
|
||||
{
|
||||
int adcReadingAverage = 0;
|
||||
|
||||
uint8_t adcChannel = channel+ ADC0_PIN;
|
||||
|
||||
for (int i = 0; i < samples; i++)
|
||||
{
|
||||
adcReadingAverage += analogRead(channel);
|
||||
adcReadingAverage += analogRead(adcChannel);
|
||||
delay(1);
|
||||
}
|
||||
|
||||
int adc3Reading = adcReadingAverage / samples;
|
||||
int adcReading = adcReadingAverage / samples;
|
||||
// Serial.print(adc3Reading);
|
||||
|
||||
// float adc3Voltage = (adc3Reading - 2528) / 220.0; // painstakingly measured
|
||||
return adc3Reading;
|
||||
return adcReading;
|
||||
}
|
||||
|
||||
int waveGen(void)
|
||||
|
@ -6,6 +6,17 @@
|
||||
#include "INA219.h"
|
||||
#include <Wire.h>
|
||||
|
||||
extern int showReadings;
|
||||
|
||||
extern int showINA0[3]; //0 = current, 1 = voltage, 2 = power
|
||||
extern int showINA1[3]; //0 = current, 1 = voltage, 2 = power
|
||||
|
||||
extern int showDAC0;
|
||||
extern int showDAC1;
|
||||
|
||||
extern int showADCreadings[4];
|
||||
|
||||
|
||||
extern int revisionNumber;
|
||||
|
||||
void initINA219(void);
|
||||
@ -26,7 +37,8 @@ int waveGen(void);
|
||||
void GetAdc29Status(int i);
|
||||
int readAdc(int channel, int samples = 10);
|
||||
|
||||
|
||||
void chooseShownReadings(void);
|
||||
void showMeasurements(int samples = 50);
|
||||
|
||||
|
||||
const uint16_t DACLookup_FullSine_9Bit[512] =
|
||||
|
@ -49,7 +49,7 @@ void setup()
|
||||
|
||||
initADC();
|
||||
delay(1);
|
||||
initDAC();
|
||||
initDAC(); // also sets revisionNumber
|
||||
delay(1);
|
||||
initINA219();
|
||||
delay(1);
|
||||
@ -87,25 +87,29 @@ void loop()
|
||||
char input;
|
||||
unsigned long timer = 0;
|
||||
|
||||
// while (1) rainbowBounce(80); //I uncomment this to test the LEDs on a fresh board
|
||||
// while (1) randomColors(0,90);
|
||||
menu:
|
||||
// showMeasurements();
|
||||
|
||||
// showLEDsCore2 = 1;
|
||||
Serial.print("\n\n\r\t\t\tMenu\n\n\r");
|
||||
Serial.print("\tn = show netlist\n\r");
|
||||
Serial.print("\tb = show bridge array\n\r");
|
||||
Serial.print("\tw = waveGen\n\r");
|
||||
// Serial.print("\tm = measure current/voltage\n\r");
|
||||
Serial.print("\tv = toggle show current/voltage\n\r");
|
||||
Serial.print("\tf = load formatted nodeFile\n\r");
|
||||
Serial.print("\tp = paste new Wokwi diagram\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("\n\r");
|
||||
Serial.print("\n\n\r");
|
||||
|
||||
dontshowmenu:
|
||||
while (Serial.available() == 0)
|
||||
;
|
||||
{
|
||||
if (showReadings >= 1)
|
||||
{
|
||||
showMeasurements();
|
||||
}
|
||||
}
|
||||
|
||||
input = Serial.read();
|
||||
|
||||
@ -114,6 +118,31 @@ menu:
|
||||
|
||||
switch (input)
|
||||
{
|
||||
case 'v':
|
||||
|
||||
if (showReadings >= 3)
|
||||
{
|
||||
showReadings = 0;
|
||||
// goto dontshowmenu;
|
||||
break;
|
||||
}
|
||||
else
|
||||
{
|
||||
showReadings++;
|
||||
chooseShownReadings();
|
||||
|
||||
Serial.write("\x1B\x5B");
|
||||
Serial.write("1F");//scroll up one line
|
||||
Serial.write("\x1B\x5B");
|
||||
Serial.write("2K");//clear line
|
||||
Serial.write("\x1B\x5B");
|
||||
Serial.write("1F");//scroll up one line
|
||||
Serial.write("\x1B\x5B");
|
||||
Serial.write("2K");//clear line
|
||||
|
||||
goto dontshowmenu;
|
||||
//break;
|
||||
}
|
||||
|
||||
case 'n':
|
||||
|
||||
@ -129,6 +158,9 @@ menu:
|
||||
Serial.print("\n\n\rChip Status\n\r");
|
||||
printChipStatus();
|
||||
Serial.print("\n\n\r");
|
||||
Serial.print("Revision ");
|
||||
Serial.print(revisionNumber);
|
||||
Serial.print("\n\n\r");
|
||||
break;
|
||||
|
||||
case 'm':
|
||||
@ -142,11 +174,11 @@ menu:
|
||||
break;
|
||||
}
|
||||
|
||||
// case 'a':
|
||||
// {
|
||||
// resetArduino(); // reset works
|
||||
// // uploadArduino(); //this is unwritten
|
||||
// }
|
||||
// case 'a':
|
||||
// {
|
||||
// resetArduino(); // reset works
|
||||
// // uploadArduino(); //this is unwritten
|
||||
// }
|
||||
|
||||
case 'f':
|
||||
digitalWrite(RESETPIN, HIGH);
|
||||
|
Loading…
Reference in New Issue
Block a user