From 7c31f864cb2f05d3b10f3f6452cad01512ab4518 Mon Sep 17 00:00:00 2001 From: noahkr07 Date: Mon, 26 Jan 2026 16:40:14 -0700 Subject: [PATCH 1/2] WPILib PDH API to AKit Conduit API --- .../java/frc/robot/util/RBSIPowerMonitor.java | 18 ++++++++++-------- 1 file changed, 10 insertions(+), 8 deletions(-) diff --git a/src/main/java/frc/robot/util/RBSIPowerMonitor.java b/src/main/java/frc/robot/util/RBSIPowerMonitor.java index 54972cf..be997f3 100644 --- a/src/main/java/frc/robot/util/RBSIPowerMonitor.java +++ b/src/main/java/frc/robot/util/RBSIPowerMonitor.java @@ -13,11 +13,12 @@ package frc.robot.util; -import edu.wpi.first.wpilibj.PowerDistribution; import edu.wpi.first.wpilibj.RobotController; import frc.robot.Constants.PowerConstants; import frc.robot.Constants.RobotDevices; import frc.robot.util.Alert.AlertType; +import org.littletonrobotics.conduit.ConduitApi; +import org.littletonrobotics.junction.LoggedPowerDistribution; import org.littletonrobotics.junction.Logger; /** @@ -29,8 +30,9 @@ public class RBSIPowerMonitor extends VirtualSubsystem { private final RBSISubsystem[] subsystems; - private final PowerDistribution m_pdm = - new PowerDistribution(PowerConstants.kPDMCANid, PowerDistribution.ModuleType.kRev); + private final LoggedPowerDistribution m_pdm = + LoggedPowerDistribution.getInstance(PowerConstants.kPDMCANid, PowerConstants.kPDMType); + ConduitApi conduit = ConduitApi.getInstance(); // Define local variables private final LoggedTunableNumber batteryCapacityAh; @@ -61,16 +63,16 @@ public RBSIPowerMonitor(LoggedTunableNumber batteryCapacityAh, RBSISubsystem... @Override public void periodic() { // --- Read voltage & total current --- - double voltage = m_pdm.getVoltage(); - double totalCurrent = m_pdm.getTotalCurrent(); + double voltage = conduit.getPDPVoltage(); + double totalCurrent = conduit.getPDPTotalCurrent(); // --- Safety alerts --- if (totalCurrent > PowerConstants.kTotalMaxCurrent) { new Alert("Total current draw exceeds limit!", AlertType.WARNING).set(true); } - for (int ch = 0; ch < m_pdm.getNumChannels(); ch++) { - double current = m_pdm.getCurrent(ch); + for (int ch = 0; ch < conduit.getPDPChannelCount(); ch++) { + double current = conduit.getPDPChannelCurrent(ch); if (current > PowerConstants.kMotorPortMaxCurrent) { new Alert("Port " + ch + " current exceeds limit!", AlertType.WARNING).set(true); } @@ -123,7 +125,7 @@ public void periodic() { private void logGroupCurrent(String name, int[] ports) { double sum = 0.0; for (int port : ports) { - sum += m_pdm.getCurrent(port); + sum += conduit.getPDPChannelCurrent(port); } Logger.recordOutput("Power/Subsystems/" + name + "Current", sum); } From 7f8a553ebb20e82ff65920062b099523fc1d8845 Mon Sep 17 00:00:00 2001 From: "Timothy P. Ellsworth Bowers" Date: Mon, 26 Jan 2026 21:24:53 -0700 Subject: [PATCH 2/2] Reinstate power logging temporarily removed --- src/main/java/frc/robot/Robot.java | 4 +++- .../java/frc/robot/util/RBSIPowerMonitor.java | 17 ++++++++--------- 2 files changed, 11 insertions(+), 10 deletions(-) diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 83d5b19..2a1bae5 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -26,8 +26,10 @@ import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; +import frc.robot.Constants.PowerConstants; import frc.robot.util.VirtualSubsystem; import org.littletonrobotics.junction.LogFileUtil; +import org.littletonrobotics.junction.LoggedPowerDistribution; import org.littletonrobotics.junction.LoggedRobot; import org.littletonrobotics.junction.Logger; import org.littletonrobotics.junction.networktables.NT4Publisher; @@ -100,7 +102,7 @@ public Robot() { // Initialize URCL Logger.registerURCL(URCL.startExternal()); StatusLogger.disableAutoLogging(); // Disable REVLib's built-in logging - // LoggedPowerDistribution.getInstance(PowerConstants.kPDMCANid, PowerConstants.kPDMType); + LoggedPowerDistribution.getInstance(PowerConstants.kPDMCANid, PowerConstants.kPDMType); // Start AdvantageKit logger Logger.start(); diff --git a/src/main/java/frc/robot/util/RBSIPowerMonitor.java b/src/main/java/frc/robot/util/RBSIPowerMonitor.java index be997f3..07987ad 100644 --- a/src/main/java/frc/robot/util/RBSIPowerMonitor.java +++ b/src/main/java/frc/robot/util/RBSIPowerMonitor.java @@ -18,7 +18,6 @@ import frc.robot.Constants.RobotDevices; import frc.robot.util.Alert.AlertType; import org.littletonrobotics.conduit.ConduitApi; -import org.littletonrobotics.junction.LoggedPowerDistribution; import org.littletonrobotics.junction.Logger; /** @@ -30,8 +29,8 @@ public class RBSIPowerMonitor extends VirtualSubsystem { private final RBSISubsystem[] subsystems; - private final LoggedPowerDistribution m_pdm = - LoggedPowerDistribution.getInstance(PowerConstants.kPDMCANid, PowerConstants.kPDMType); + // private final LoggedPowerDistribution m_pdm = + // LoggedPowerDistribution.getInstance(PowerConstants.kPDMCANid, PowerConstants.kPDMType); ConduitApi conduit = ConduitApi.getInstance(); // Define local variables @@ -78,12 +77,12 @@ public void periodic() { } } - // if (voltage < PowerConstants.kVoltageWarning) { - // new Alert("Low battery voltage!", AlertType.WARNING).set(true); - // } - // if (voltage < PowerConstants.kVoltageCritical) { - // new Alert("Critical battery voltage!", AlertType.ERROR).set(true); - // } + if (voltage < PowerConstants.kVoltageWarning) { + new Alert("Low battery voltage!", AlertType.WARNING).set(true); + } + if (voltage < PowerConstants.kVoltageCritical) { + new Alert("Critical battery voltage!", AlertType.ERROR).set(true); + } // --- Battery estimation --- long nowUs = RobotController.getFPGATime();