Skip to content
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 12 additions & 1 deletion src/main/java/frc/robot/constants/BattMonConstants.java
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
Copy link
Contributor Author

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):

  • kVolt1
  • kDutyVolt1
  • kVolt2
  • kDutyVolt2

Then the following constants can be calculated in the constants file using those 4 constants (replacing batt and volt with the appropriate naming)

  • kBattVoltSlope
  • kBattVoltOffset

Copy link
Contributor Author

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

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;
}
33 changes: 32 additions & 1 deletion src/main/java/frc/robot/subsystems/battMon/BattMonHardware.java
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);
private DigitalInput batt2 = new DigitalInput(1);
private DigitalInput PDP = new DigitalInput(3);
private DigitalInput temp = new DigitalInput(4);
private DutyCycle batt1Cycle = new DutyCycle(batt1);
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) {
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))
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

can you change 1000000000 to 1_000_000_000 instead for readability?

* BattMonConstants.kTemp;
}
}
15 changes: 14 additions & 1 deletion src/main/java/frc/robot/subsystems/battMon/BattMonIO.java
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 {
public double batt1Output;
public double batt2Output;
public double pdpOutput ;
public double tempOutput ;
}

public default void updateInputs(BattMonIOInputs inputs) {}
}
53 changes: 52 additions & 1 deletion src/main/java/frc/robot/subsystems/battMon/BattMonSubsystem.java
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 {
Copy link
Contributor Author

Choose a reason for hiding this comment

The 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() {
Copy link
Contributor Author

Choose a reason for hiding this comment

The 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
we may end up wanting averages of voltages/currents as well

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy link
Contributor Author

Choose a reason for hiding this comment

The 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
Should record the averaged temp as an output

//Refresh data and graph it
io.updateInputs(inputs);

//Check for dangerous outputs NOTE all of these values are temporary
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You aren't actually using your state machine here...

In NORMAL

  • calculate the DANGER and WARNING temperature limits based on the current drawn (tLim = temp * slope + offset), WARNING = XX below DANGER
  • check if temp is greater than DANGER
    • set appropriate alert
    • calculate recoveryTemp based on current DANGER limit and save it off
    • transition to DANGER
  • check if temp is greater than WARNING
    • set appropriate alert
    • calculate recoveryTemp based on current WARNING limit and save it off
    • transition to WARNING

In WARNING:

  • calculate current DANGER threshold based on current
  • check if temp is above DANGER threshold if so:
    • save off recoveryTemp (xx deg below current DANGER threshold)
    • set appropriate alerts
    • change state to DANGER
  • check if temp is below the saved recoveryTemp, if so:
    • clear the appropriate alerts
    • switch states back to NORMAL

In DANGER:

  • check if the current temp is below the saved recoveryTemp if so:
    • switch back to NORMAL
    • clear the appropriate alerts

if (inputs.batt1Output > 1000){
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If we are trying to have a low battery threshold, that alert should be set based on a constant, not a magic # in code

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
}

}

Loading