Skip to content

Commit

Permalink
some logging things
Browse files Browse the repository at this point in the history
  • Loading branch information
Ishan1522 committed Nov 2, 2024
1 parent 52fbf88 commit 53d0bec
Show file tree
Hide file tree
Showing 7 changed files with 848 additions and 14 deletions.
22 changes: 12 additions & 10 deletions src/main/java/frc/robot/BuildConstants.java
Original file line number Diff line number Diff line change
@@ -1,17 +1,19 @@
package frc.robot;

/** Automatically generated file containing build version information. */
/**
* Automatically generated file containing build version information.
*/
public final class BuildConstants {
public static final String MAVEN_GROUP = "";
public static final String MAVEN_NAME = "4829-BaseRobotCode-1";
public static final String MAVEN_NAME = "4829-BaseRobotCode-2";
public static final String VERSION = "unspecified";
public static final int GIT_REVISION = 32;
public static final String GIT_SHA = "71a47d311fd066ba3b76be8d09eff3e03b893cd8";
public static final String GIT_DATE = "2024-10-28 22:21:12 EDT";
public static final String GIT_BRANCH = "docs";
public static final String BUILD_DATE = "2024-10-29 16:56:45 EDT";
public static final long BUILD_UNIX_TIME = 1730235405242L;
public static final int DIRTY = 0;
public static final int GIT_REVISION = 8;
public static final String GIT_SHA = "52fbf88798bd786d25dffff6b4769182ad9ea51c";
public static final String GIT_DATE = "2024-10-29 17:58:37 EDT";
public static final String GIT_BRANCH = "main";
public static final String BUILD_DATE = "2024-11-02 06:46:02 EDT";
public static final long BUILD_UNIX_TIME = 1730544362283L;
public static final int DIRTY = 1;

private BuildConstants() {}
private BuildConstants(){}
}
8 changes: 5 additions & 3 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,8 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import frc.robot.Constants.Mode;
import frc.robot.extras.UnitTestableRobot;

import org.littletonrobotics.junction.LoggedRobot;
import org.littletonrobotics.junction.Logger;
import org.littletonrobotics.junction.networktables.NT4Publisher;
Expand All @@ -20,11 +22,11 @@
* the package after creating this project, you must also update the build.gradle file in the
* project.
*/
public class Robot extends LoggedRobot {
public class Robot extends UnitTestableRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
private static final Mode JAVA_SIM_MODE = Mode.SIM;
public static final Mode CURRENT_ROBOT_MODE = isReal() ? Mode.REAL : JAVA_SIM_MODE;
private static final Mode JAVA_SIM_MODE = Mode.TEST;
public static final Mode CURRENT_ROBOT_MODE = isReal() ? Mode.TELEOP : JAVA_SIM_MODE;

/**
* This function is run when the robot is first started up and should be used for any
Expand Down
331 changes: 331 additions & 0 deletions src/main/java/frc/robot/extras/UnitTestableRobot.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,331 @@
package frc.robot.extras;

import java.util.Optional;
import java.util.concurrent.atomic.AtomicBoolean;
import java.util.function.Consumer;
import java.util.function.DoubleSupplier;

import org.littletonrobotics.junction.LoggedRobot;

import frc.robot.extras.debug.Tracer;

import edu.wpi.first.hal.DriverStationJNI;
import edu.wpi.first.hal.HAL;
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.simulation.DriverStationSim;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.CommandScheduler;

/**
* A way to run your *whole* robot code in a unit test.
*
* This allows you to hook onto to any of the robot mode functions and run your own code.
*
* This also allows you to interupt the robot code in a way without the unit test thinking it crashed.
*
* <pre><code>
*
* @Test
* public void testAuto(@Robo Robot robot) {
* RobotSetup.testOverrideRobotID(RobotID.SIM_CRASH);
* Pose2d desiredEndPose = new Pose2d(
* new Translation2d(3.0, 7.0),
* new Rotation2d());
* DriverStationSim.setAllianceStationId(AllianceStationID.Blue1);
* // meters
* final double translationTolerance = 0.2;
* Autos.setAutoOverrideTest(new ProxyCommand(() -> new PathPlannerAuto("1 Meter Auto")));
* DriverStationSim.setAutonomous(true);
* DriverStationSim.setEnabled(true);
* robot.withAutonomousPeriodicTest(robo -> {
* boolean isFinished = GlobalState.getLocalizedPose()
* .getTranslation()
* .getDistance(desiredEndPose.getTranslation()) < translationTolerance;
* if (isFinished) {
* robo.finishUnitTestRobot();
* } else if (robo.getElapsedTime() > 2.5) {
* throw new RuntimeException(
* "Auto took to long, ended at "
* + GlobalState.getLocalizedPose().toString());
* }
* });
* robot.runTest(3);
* System.gc();
* }
*
* </code></pre>
*
*/
public abstract class UnitTestableRobot<R extends UnitTestableRobot<R>> extends LoggedRobot {
private static Optional<Boolean> cachedIsTest = Optional.empty();
public static boolean isUnitTest() {
if (cachedIsTest.isEmpty()) {
cachedIsTest = Optional.of(System.getenv("test") != null);
}
return cachedIsTest.get();
}

public static class UnitTestableRobotExited extends RuntimeException {
private static final long serialVersionUID = 1L;

public UnitTestableRobotExited() {
super("Unit test robot exited properly");
}
}

public static class UnitTestableRobotTimedOut extends RuntimeException {
private static final long serialVersionUID = 1L;

public UnitTestableRobotTimedOut() {
super("Unit test robot timed out");
}
}

public static enum Mode {
NONE,
DISABLED,
AUTONOMOUS,
TELEOP,
TEST
}

private AtomicBoolean killswitch = new AtomicBoolean(false);

Check warning on line 101 in src/main/java/frc/robot/extras/UnitTestableRobot.java

View workflow job for this annotation

GitHub Actions / Lint

Field 'killswitch' may be declared final

Reports non-final fields whose value never changes once object initialization ends, and hence may be marked final. Note that this rule does not enforce that the field value be deeply immutable itself. An object can still have mutable state, even if all its member fields are declared final. This is referred to as shallow immutability. For more information on mutability, see *Effective Java, 3rd Edition, Item 17: Minimize mutability*. Limitations: We can only check private fields for now. ImmutableField (Priority: 3, Ruleset: Design) https://docs.pmd-code.org/pmd-doc-7.7.0/pmd_rules_java_design.html#immutablefield

private final Timer timer = new Timer();
private double timeoutDuration = 30.0;

private Mode lastMode = Mode.NONE;
private boolean calledDsConnected = false;

Check warning on line 107 in src/main/java/frc/robot/extras/UnitTestableRobot.java

View workflow job for this annotation

GitHub Actions / Lint

Avoid using redundant field initializer for 'calledDsConnected'

Java will initialize fields with known default values so any explicit initialization of those same defaults is redundant and results in a larger class file (approximately three additional bytecode instructions per field). RedundantFieldInitializer (Priority: 3, Ruleset: Performance) https://docs.pmd-code.org/pmd-doc-7.7.0/pmd_rules_java_performance.html#redundantfieldinitializer
private int loopCount = 0;

Check warning on line 108 in src/main/java/frc/robot/extras/UnitTestableRobot.java

View workflow job for this annotation

GitHub Actions / Lint

Avoid using redundant field initializer for 'loopCount'

Java will initialize fields with known default values so any explicit initialization of those same defaults is redundant and results in a larger class file (approximately three additional bytecode instructions per field). RedundantFieldInitializer (Priority: 3, Ruleset: Performance) https://docs.pmd-code.org/pmd-doc-7.7.0/pmd_rules_java_performance.html#redundantfieldinitializer

private Optional<Consumer<R>> disabledInitTest = Optional.empty();
private Optional<Consumer<R>> autonomousInitTest = Optional.empty();
private Optional<Consumer<R>> teleopInitTest = Optional.empty();

private Optional<Consumer<R>> disabledPeriodicTest = Optional.empty();
private Optional<Consumer<R>> autonomousPeriodicTest = Optional.empty();
private Optional<Consumer<R>> teleopPeriodicTest = Optional.empty();

private Optional<Consumer<R>> disabledExitTest = Optional.empty();
private Optional<Consumer<R>> autonomousExitTest = Optional.empty();
private Optional<Consumer<R>> teleopExitTest = Optional.empty();

public UnitTestableRobot(double period) {
super(
new DoubleSupplier() {
@Override
public double getAsDouble() {
if (isUnitTest()) assert HAL.initialize(500, 0);
return period;
}
}.getAsDouble()
);
if (isUnitTest()) {
DriverStationSim.setEnabled(false);
DriverStationSim.setAutonomous(false);
DriverStationSim.setTest(false);
DriverStationSim.setDsAttached(true);
}
}

public void finishUnitTestRobot() {
killswitch.set(true);
}

public void runTest(double timeout) {
this.timeoutDuration = timeout;
timer.start();
try {
this.startCompetition();
} catch (UnitTestableRobotExited e) {
// Expected
}
this.endCompetition();
this.close();
if (isUnitTest()) {
HAL.exitMain();
HAL.shutdown();
var cmdScheduler = CommandScheduler.getInstance();
cmdScheduler.cancelAll();
cmdScheduler.getActiveButtonLoop().clear();
cmdScheduler.getDefaultButtonLoop().clear();
cmdScheduler.clearComposedCommands();
cmdScheduler.unregisterAllSubsystems();
}
}

@SuppressWarnings("unchecked")
@Override
protected void loopFunc() {
Tracer.startTrace("RobotLoop");
if (isUnitTest()) {
if (killswitch.get()) {
throw new UnitTestableRobotExited();
}
if (timer.hasElapsed(timeoutDuration)) {
throw new UnitTestableRobotTimedOut();
}
}
DriverStation.refreshData();
// Get current mode
Mode mode = Mode.NONE;
if (DriverStation.isDisabled()) {
mode = Mode.DISABLED;
} else if (DriverStation.isAutonomous()) {
mode = Mode.AUTONOMOUS;
} else if (DriverStation.isTeleop()) {
mode = Mode.TELEOP;
} else if (DriverStation.isTest()) {
mode = Mode.TEST;
}

if ((!calledDsConnected && DriverStation.isDSAttached()) || isUnitTest()) {
calledDsConnected = true;
driverStationConnected();
}

// If mode changed, call mode exit and entry functions
if (lastMode != mode) {
// Call last mode's exit function
if (lastMode == Mode.DISABLED) {
disabledExit();
disabledExitTest.ifPresent(test -> test.accept(((R) this)));
} else if (lastMode == Mode.AUTONOMOUS) {
autonomousExit();
autonomousExitTest.ifPresent(test -> test.accept(((R) this)));
} else if (lastMode == Mode.TELEOP) {
teleopExit();
teleopExitTest.ifPresent(test -> test.accept(((R) this)));
} else if (lastMode == Mode.TEST) {
testExit();
teleopExitTest.ifPresent(test -> test.accept(((R) this)));
}

// Call current mode's entry function
if (mode == Mode.DISABLED) {
disabledInit();
disabledInitTest.ifPresent(test -> test.accept(((R) this)));
} else if (mode == Mode.AUTONOMOUS) {
autonomousInit();
autonomousInitTest.ifPresent(test -> test.accept(((R) this)));
} else if (mode == Mode.TELEOP) {
teleopInit();
teleopInitTest.ifPresent(test -> test.accept(((R) this)));
} else if (mode == Mode.TEST) {
testInit();
teleopInitTest.ifPresent(test -> test.accept(((R) this)));
}

lastMode = mode;
}

// Call the appropriate function depending upon the current robot mode
if (mode == Mode.DISABLED) {
DriverStationJNI.observeUserProgramDisabled();
Tracer.traceFunc("disabledPeriodic", this::disabledPeriodic);
disabledPeriodicTest.ifPresent(test -> test.accept(((R) this)));
} else if (mode == Mode.AUTONOMOUS) {
DriverStationJNI.observeUserProgramAutonomous();
Tracer.traceFunc("autonomousPeriodic", this::autonomousPeriodic);
autonomousPeriodicTest.ifPresent(test -> test.accept(((R) this)));
} else if (mode == Mode.TELEOP) {
DriverStationJNI.observeUserProgramTeleop();
Tracer.traceFunc("teleopPeriodic", this::teleopPeriodic);
teleopPeriodicTest.ifPresent(test -> test.accept(((R) this)));
} else {
DriverStationJNI.observeUserProgramTest();
Tracer.traceFunc("testPeriodic", this::testPeriodic);
teleopPeriodicTest.ifPresent(test -> test.accept(((R) this)));
}

Tracer.traceFunc("robotPeriodic", this::robotPeriodic);

SmartDashboard.updateValues();

if (isSimulation()) {
HAL.simPeriodicBefore();
simulationPeriodic();
HAL.simPeriodicAfter();
}

NetworkTableInstance.getDefault().flushLocal();

Tracer.endTrace();
loopCount++;
}

public UnitTestableRobot<R> withDisableInitTest(Consumer<R> testInit) {
if (isUnitTest())
this.disabledInitTest = Optional.of(testInit);
return this;
}

public UnitTestableRobot<R> withAutonomousInitTest(Consumer<R> testInit) {
if (isUnitTest())
this.autonomousInitTest = Optional.of(testInit);
return this;
}

public UnitTestableRobot<R> withTeleopInitTest(Consumer<R> testInit) {
if (isUnitTest())
this.teleopInitTest = Optional.of(testInit);
return this;
}

public UnitTestableRobot<R> withDisablePeriodicTest(Consumer<R> testPeriodic) {
if (isUnitTest())
this.disabledPeriodicTest = Optional.of(testPeriodic);
return this;
}

public UnitTestableRobot<R> withAutonomousPeriodicTest(Consumer<R> testPeriodic) {
if (isUnitTest())
this.autonomousPeriodicTest = Optional.of(testPeriodic);
return this;
}

public UnitTestableRobot<R> withTeleopPeriodicTest(Consumer<R> testPeriodic) {
if (isUnitTest())
this.teleopPeriodicTest = Optional.of(testPeriodic);
return this;
}

public UnitTestableRobot<R> withDisableExitTest(Consumer<R> testExit) {
if (isUnitTest())
this.disabledExitTest = Optional.of(testExit);
return this;
}

public UnitTestableRobot<R> withAutonomousExitTest(Consumer<R> testExit) {
if (isUnitTest())
this.autonomousExitTest = Optional.of(testExit);
return this;
}

public UnitTestableRobot<R> withTeleopExitTest(Consumer<R> testExit) {
if (isUnitTest())
this.teleopExitTest = Optional.of(testExit);
return this;
}

public Mode getMode() {
return lastMode;
}

public int getLoopCount() {
return loopCount;
}

public double getElapsedTime() {
return timer.get();
}
}
Loading

0 comments on commit 53d0bec

Please sign in to comment.