Skip to content

Commit 0809c7b

Browse files
Fixed everything
1 parent a7f0d97 commit 0809c7b

File tree

4 files changed

+36
-26
lines changed

4 files changed

+36
-26
lines changed

src/main/java/frc/robot/constants/BattMonConstants.java

Lines changed: 11 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -2,13 +2,19 @@
22

33
public class BattMonConstants {
44
// All of these aren't right and will need to be determined
5-
public static double kBatt1 = 42;
6-
public static double kBatt2 = 42;
7-
public static double kPDP = 42;
8-
public static double kTemp = 42;
5+
public static double kBattVolt1 = 42;
6+
public static double kBattVolt2;
7+
public static double kBattCurrent1 = 42;
8+
public static double kBattCurrent2;
9+
public static double kPdpVoltage1 = 42;
10+
public static double kPdpVoltage2;
11+
public static double kBreakerTemp1 = 0.32;
12+
public static double kBreakerTemp2 = 0.0047;
913

1014
public static double kBatt1Low = 2;
1115
public static double kBatt2Low = 2;
1216
public static double kPDPHigh = 42;
13-
public static double kTempHigh = 300;
17+
public static double kTempHighSlope = 10;
18+
public static double kTempDangerSlope = 15;
19+
public static double kHysteresis= 1;
1420
}

src/main/java/frc/robot/subsystems/battMon/BattMonHardware.java

Lines changed: 15 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -7,13 +7,13 @@
77

88
public class BattMonHardware implements BattMonIO {
99

10-
private DigitalInput batt1 = new DigitalInput(0);
11-
private DigitalInput batt2 = new DigitalInput(1);
12-
private DigitalInput PDP = new DigitalInput(3);
10+
private DigitalInput battVoltage = new DigitalInput(0);
11+
private DigitalInput battCurrent = new DigitalInput(1);
12+
private DigitalInput pdpVoltage = new DigitalInput(3);
1313
private DigitalInput temp = new DigitalInput(4);
14-
private DutyCycle batt1Cycle = new DutyCycle(batt1);
15-
private DutyCycle batt2Cycle = new DutyCycle(batt2);
16-
private DutyCycle PDPCycle = new DutyCycle(PDP);
14+
private DutyCycle battVoltageCycle = new DutyCycle(battVoltage);
15+
private DutyCycle battCurrentCycle = new DutyCycle(battCurrent);
16+
private DutyCycle pdpCycle = new DutyCycle(pdpVoltage);
1717
private DutyCycle tempCycle = new DutyCycle(temp);
1818

1919
private Counter tempCounter = new Counter(temp);
@@ -24,11 +24,14 @@ public BattMonHardware() {
2424

2525
@Override
2626
public void updateInputs(BattMonIOInputs inputs) {
27-
inputs.batt1Output = batt1Cycle.getOutput() * BattMonConstants.kBatt1;
28-
inputs.batt2Output = batt2Cycle.getOutput() * BattMonConstants.kBatt2;
29-
inputs.pdpOutput = PDPCycle.getOutput() * BattMonConstants.kPDP;
30-
inputs.tempOutput =
31-
(tempCycle.getHighTimeNanoseconds() / (tempCounter.getPeriod() / 1000000000))
32-
* BattMonConstants.kTemp;
27+
inputs.batteryVoltage = battVoltageCycle.getOutput()
28+
* BattMonConstants.kBattVolt1 * BattMonConstants.kBattVolt2;
29+
inputs.batteryCurrent = battCurrentCycle.getOutput()
30+
* BattMonConstants.kBattCurrent1 * BattMonConstants.kBattCurrent2;
31+
inputs.pdpVoltage = pdpCycle.getOutput()
32+
* BattMonConstants.kPdpVoltage1 * BattMonConstants.kPdpVoltage2;
33+
inputs.breakerTemp =
34+
((tempCycle.getHighTimeNanoseconds() / (tempCounter.getPeriod() / 1000000000))
35+
- BattMonConstants.kBreakerTemp1) / BattMonConstants.kBreakerTemp2;
3336
}
3437
}

src/main/java/frc/robot/subsystems/battMon/BattMonIO.java

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -6,10 +6,10 @@ public interface BattMonIO {
66

77
@AutoLog
88
public class BattMonIOInputs {
9-
public double batt1Output;
10-
public double batt2Output;
11-
public double pdpOutput;
12-
public double tempOutput;
9+
public double batteryVoltage;
10+
public double batteryCurrent;
11+
public double pdpVoltage;
12+
public double breakerTemp;
1313
}
1414

1515
public default void updateInputs(BattMonIOInputs inputs) {}

src/main/java/frc/robot/subsystems/battMon/BattMonSubsystem.java

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
import edu.wpi.first.wpilibj.Alert;
44
import edu.wpi.first.wpilibj.Alert.AlertType;
55
import edu.wpi.first.wpilibj2.command.SubsystemBase;
6+
import frc.robot.constants.BattMonConstants;
67
import frc.robot.subsystems.battMon.BattMonIO.BattMonIOInputs;
78

89
public class BattMonSubsystem extends SubsystemBase {
@@ -25,21 +26,21 @@ public void periodic() {
2526
// Check for dangerous outputs NOTE all of these values are temporary
2627
switch (curState) {
2728
case NORMAL:
28-
if (inputs.tempOutput >= (1000 * inputs.pdpOutput)) {
29+
if (inputs.breakerTemp >= (BattMonConstants.kTempHighSlope * inputs.pdpVoltage + 100)) {
2930
highTempAlert.set(true);
3031
safeAlert.set(false);
31-
tempThreshold = inputs.tempOutput - (100 * inputs.pdpOutput);
32+
tempThreshold = inputs.breakerTemp - BattMonConstants.kHysteresis * inputs.pdpVoltage;
3233
curState = battMonState.WARNING;
3334
} else {
3435
break;
3536
}
3637

3738
case WARNING:
38-
if (inputs.tempOutput > (2000 * inputs.pdpOutput)) {
39+
if (inputs.breakerTemp > (BattMonConstants.kTempDangerSlope * inputs.pdpVoltage)) {
3940
highTempAlert.set(false);
4041
dangerTempAlert.set(true);
4142
curState = battMonState.DANGER;
42-
} else if (inputs.tempOutput < tempThreshold) {
43+
} else if (inputs.breakerTemp < tempThreshold) {
4344
highTempAlert.set(false);
4445
safeAlert.set(true);
4546
curState = battMonState.NORMAL;
@@ -48,7 +49,7 @@ public void periodic() {
4849
}
4950

5051
case DANGER:
51-
if (inputs.tempOutput >= (2000 * inputs.pdpOutput)) {
52+
if (inputs.breakerTemp >= (BattMonConstants.kTempDangerSlope * inputs.pdpVoltage)) {
5253
break;
5354
} else {
5455
dangerTempAlert.set(false);

0 commit comments

Comments
 (0)