Skip to content

Commit

Permalink
Added advantage kit modes for robot.java
Browse files Browse the repository at this point in the history
  • Loading branch information
DerekChen1 committed Dec 5, 2023
1 parent b9d3a89 commit 098cc25
Show file tree
Hide file tree
Showing 4 changed files with 45 additions and 0 deletions.
8 changes: 8 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,14 @@ public static final class Config {
Filesystem.getDeployDirectory().toPath().resolve("poseEstimationsAtDistances.csv");
public static final double REAL_X = 0.0;
public static final double REAL_Y = 0.0;

public static final advantageKitModes currentAdvMode = advantageKitModes.REAL;

public static enum advantageKitModes {
REAL,
SIM,
REPLAY
};
}

public static final class Drive {
Expand Down
26 changes: 26 additions & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,24 @@ public void robotInit() {

Logger.getInstance().recordMetadata("ProjectName", "MyProject"); // Set a metadata value

switch (Constants.Config.currentAdvMode) {
case REAL:
// Running on a real robot, log to a USB stick
Logger.getInstance().addDataReceiver(new WPILOGWriter("/U"));
Logger.getInstance().addDataReceiver(new NT4Publisher());
break;
case SIM:
Logger.getInstance().addDataReceiver(new NT4Publisher());
break;
case REPLAY:
// Replaying a log, set up replay source
setUseTiming(false); // Run as fast as possible
String logPath = LogFileUtil.findReplayLog();
Logger.getInstance().setReplaySource(new WPILOGReader(logPath));
Logger.getInstance()
.addDataReceiver(new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim")));
break;
}
if (super.isReal()) {
Logger.getInstance().addDataReceiver(new WPILOGWriter("/U")); // Log to a USB stick
Logger.getInstance().addDataReceiver(new NT4Publisher()); // Publish data to NetworkTables
Expand Down Expand Up @@ -154,4 +172,12 @@ public void testInit() {
public void testPeriodic() {
// This method intentionally left empty
}

/** This function is called once when the robot is first started up. */
@Override
public void simulationInit() {}

/** This function is called periodically whilst in simulation. */
@Override
public void simulationPeriodic() {}
}
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

public interface DrivebaseSubsystemIO {
@AutoLog
// This does not work
public static class DrivebaseSubsystemIOInputs {
public double frontLeftPositionRad = 0.0;
public double frontLeftVelocityRadPerSec = 0.0;
Expand Down
10 changes: 10 additions & 0 deletions src/main/java/frc/robot/subsystems/IntakeIOSim.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
package frc.robot.subsystems;

import edu.wpi.first.wpilibj.simulation.FlywheelSim;

public class IntakeIOSim implements IntakeIO {
// Note: Intakes have no simulation feature, so this simulation class is only here as a
// placeholder. To see an actual simulation, go to
// https://github.dev/Mechanical-Advantage/RobotCode2022/blob/main/src/main/java/frc/robot/subsystems and look at the simulations that have been implemented
private FlywheelSim sim = new FlywheelSim(null, 0, 0);
}

0 comments on commit 098cc25

Please sign in to comment.