-
Notifications
You must be signed in to change notification settings - Fork 0
Initial Battery Monitor Subsystem #2
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Changes from 2 commits
b9f710f
25c4417
a7f0d97
0809c7b
225cbc8
8be75f4
f91adac
0185abb
48472e2
78b9af9
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -1,3 +1,14 @@ | ||
| package frc.robot.constants; | ||
|
|
||
| public class BattMonConstants {} | ||
| public class BattMonConstants { | ||
| //All of these aren't right and will need to be determined | ||
| public static double kBatt1 = 42; | ||
| public static double kBatt2 = 42; | ||
| public static double kPDP = 42; | ||
| public static double kTemp = 42; | ||
|
|
||
| public static double kBatt1Low = 2; | ||
| public static double kBatt2Low = 2; | ||
| public static double kPDPHigh = 42; | ||
| public static double kTempHigh = 300; | ||
| } | ||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -1,3 +1,34 @@ | ||
| package frc.robot.subsystems.battMon; | ||
|
|
||
| public class BattMonHardware {} | ||
| import edu.wpi.first.wpilibj.Counter; | ||
| import edu.wpi.first.wpilibj.DigitalInput; | ||
| import edu.wpi.first.wpilibj.DutyCycle; | ||
| import frc.robot.constants.BattMonConstants; | ||
|
|
||
| public class BattMonHardware implements BattMonIO { | ||
|
|
||
| private DigitalInput batt1 = new DigitalInput(0); | ||
mwitcpalek marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| private DigitalInput batt2 = new DigitalInput(1); | ||
mwitcpalek marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| private DigitalInput PDP = new DigitalInput(3); | ||
mwitcpalek marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| private DigitalInput temp = new DigitalInput(4); | ||
| private DutyCycle batt1Cycle = new DutyCycle(batt1); | ||
mwitcpalek marked this conversation as resolved.
Outdated
Show resolved
Hide resolved
|
||
| private DutyCycle batt2Cycle = new DutyCycle(batt2); | ||
| private DutyCycle PDPCycle = new DutyCycle(PDP); | ||
| private DutyCycle tempCycle = new DutyCycle(temp); | ||
|
|
||
| private Counter tempCounter = new Counter(temp); | ||
|
|
||
| public BattMonHardware() { | ||
| tempCounter.setUpSourceEdge(true, false); | ||
| } | ||
|
|
||
| @Override | ||
| public void updateInputs(BattMonIOInputs inputs) { | ||
mwitcpalek marked this conversation as resolved.
Show resolved
Hide resolved
|
||
| inputs.batt1Output = batt1Cycle.getOutput() * BattMonConstants.kBatt1; | ||
| inputs.batt2Output = batt2Cycle.getOutput() * BattMonConstants.kBatt2; | ||
| inputs.pdpOutput = PDPCycle.getOutput() * BattMonConstants.kPDP; | ||
| inputs.tempOutput = | ||
| (tempCycle.getHighTimeNanoseconds() / (tempCounter.getPeriod() / 1000000000)) | ||
|
||
| * BattMonConstants.kTemp; | ||
| } | ||
| } | ||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -1,3 +1,16 @@ | ||
| package frc.robot.subsystems.battMon; | ||
|
|
||
| public class BattMonIO {} | ||
| import org.littletonrobotics.junction.AutoLog; | ||
|
|
||
| public interface BattMonIO { | ||
|
|
||
| @AutoLog | ||
| public class BattMonIOInputs { | ||
mwitcpalek marked this conversation as resolved.
Show resolved
Hide resolved
|
||
| public double batt1Output; | ||
| public double batt2Output; | ||
| public double pdpOutput ; | ||
| public double tempOutput ; | ||
| } | ||
|
|
||
| public default void updateInputs(BattMonIOInputs inputs) {} | ||
| } | ||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -1,3 +1,54 @@ | ||
| package frc.robot.subsystems.battMon; | ||
|
|
||
| public class BattMonSubsystem {} | ||
| import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||
| import frc.robot.subsystems.battMon.BattMonIO.BattMonIOInputs; | ||
| import edu.wpi.first.wpilibj.Alert; | ||
| import edu.wpi.first.wpilibj.Alert.AlertType; | ||
|
|
||
| public class BattMonSubsystem extends SubsystemBase { | ||
|
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. going to need a getState() method for the robotStateSubsystem to interact with this one |
||
| //Private objects | ||
| private BattMonIO io; | ||
| private BattMonIOInputs inputs = new BattMonIOInputs(); | ||
| //Alerts | ||
| private Alert lowBattAlert = new Alert("WARNING low battery", AlertType.kWarning); | ||
| private Alert highTempAlert = new Alert("WARNING reaching maximum temp!", AlertType.kWarning); | ||
| private Alert dangerTempAlert = new Alert("DANGER MAXIMUM TEMP REACHED", AlertType.kError); | ||
| private Alert safeAgainAlert = new Alert("SAFE Temp low. Limits removed", AlertType.kInfo); | ||
|
|
||
| @Override | ||
| public void periodic() { | ||
|
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. you are going to want a running average of the temperature to work off of as that signal is quite noisy
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Could use this class in wpilib: https://github.wpilib.org/allwpilib/docs/release/java/edu/wpi/first/math/filter/LinearFilter.html#movingAverage(int)
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Would want to make all of the decisions about current limiting on the averaged temp |
||
| //Refresh data and graph it | ||
| io.updateInputs(inputs); | ||
|
|
||
mwitcpalek marked this conversation as resolved.
Show resolved
Hide resolved
|
||
| //Check for dangerous outputs NOTE all of these values are temporary | ||
|
||
| if (inputs.batt1Output > 1000){ | ||
|
||
| lowBattAlert.set(true); | ||
| }else { | ||
| lowBattAlert.set(false); | ||
| } | ||
|
|
||
| if (inputs.tempOutput > (1000 * inputs.pdpOutput)){ | ||
| highTempAlert.set(true); | ||
| safeAgainAlert.set(false); | ||
| }else if (inputs.tempOutput > (2000 * inputs.pdpOutput) | ||
| && inputs.tempOutput < (1000 * inputs.pdpOutput)) { | ||
| highTempAlert.set(false); | ||
| dangerTempAlert.set(true); | ||
| }else { | ||
| highTempAlert.set(false); | ||
| dangerTempAlert.set(false); | ||
| safeAgainAlert.set(true); | ||
| } | ||
|
|
||
| } | ||
|
|
||
| public enum battMonStates { | ||
|
|
||
| NORMAL,//Safe Temp | ||
| WARNING,//Reaching Dangerous temps | ||
| DANGER,//Dangerous temps | ||
| BATTLOW //Low Battery | ||
| } | ||
|
|
||
| } | ||
|
|
||
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I think you are probably going to need the following constants:
For voltage/current measurements (replacing volt where appropriate):
Then the following constants can be calculated in the constants file using those 4 constants (replacing batt and volt with the appropriate naming)
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Temperature is going to need 2 constants that we can get straight from the datasheet of the sensor
Temp = (dutyCycle - 0.32)/0.0047