Skip to content
Merged
Show file tree
Hide file tree
Changes from all 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
11 changes: 8 additions & 3 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,6 @@ public final class Constants {
public static final Mode simMode = Mode.SIM;
public static final Mode currentMode = RobotBase.isReal() ? Mode.REAL : simMode;

/** Enable to print loop timing when total exceeds 20ms. */
public static final boolean PROFILING_ENABLED = false;

public static enum Mode {
/** Running on a real robot. */
REAL,
Expand All @@ -42,6 +39,14 @@ public static enum Mode {
REPLAY
}

public static final class FeatureFlags {
/** Enable to print loop timing when total exceeds 20ms. */
public static final boolean PROFILING_ENABLED = false;

/** Set to false to disable the hopper subsystem entirely. */
public static final boolean kHopperEnabled = true;
}

public final class RobotConstants {
public static final double kNominalVoltage = 12.0;
}
Expand Down
53 changes: 29 additions & 24 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
import frc.lib.LoggedPowerDistribution;
import frc.lib.ZorroController.Axis;
import frc.robot.Constants.DIOPorts;
import frc.robot.Constants.FeatureFlags;
import frc.robot.auto.B_LeftTrenchAuto;
import frc.robot.auto.B_LeftTrenchMoveFirstAuto;
import frc.robot.auto.B_RightTrenchAuto;
Expand Down Expand Up @@ -195,7 +196,7 @@ public Robot() {
new TurretIOSpark(),
new FlywheelIOTalonFX(),
new HoodIOSpark());
hopper = new Hopper(new HopperIOReal());
if (FeatureFlags.kHopperEnabled) hopper = new Hopper(new HopperIOReal());
intake =
new Intake(
new RollerIOTalonFX(RollerConstants.upperRollerConfig),
Expand Down Expand Up @@ -241,7 +242,7 @@ public Robot() {
new FlywheelIOSimTalonFX(),
new HoodIOSimSpark());
feeder = new Feeder(new SpindexerIOSimSpark(), new KickerIOSimSpark());
hopper = new Hopper(new HopperIOSim());
if (FeatureFlags.kHopperEnabled) hopper = new Hopper(new HopperIOSim());
var intakeArmIOSim = new IntakeArmIOSim();
intake =
new Intake(
Expand Down Expand Up @@ -283,7 +284,7 @@ public Robot() {
new TurretIO() {},
new FlywheelIO() {},
new HoodIO() {});
hopper = new Hopper(new HopperIO() {});
if (FeatureFlags.kHopperEnabled) hopper = new Hopper(new HopperIO() {});
intake = new Intake(new RollerIO() {}, new RollerIO() {}, new IntakeArmIO() {});
feeder = new Feeder(new SpindexerIO() {}, new KickerIO() {});
break;
Expand All @@ -302,12 +303,14 @@ public Robot() {

// Wire the hopper/intake interlocks. Done here (after both subsystems exist) to avoid a
// circular dependency between the two subsystems.
intake.setDeployInterlock(
hopper::isDeployed,
() -> hopper.getDeployCommand().withTimeout(IntakeConstants.kInterlockSettleSeconds));
hopper.setRetractInterlock(
intake::isStowed,
() -> intake.getStopCommand().withTimeout(IntakeConstants.kInterlockSettleSeconds));
if (FeatureFlags.kHopperEnabled) {
intake.setDeployInterlock(
hopper::isDeployed,
() -> hopper.getDeployCommand().withTimeout(IntakeConstants.kInterlockSettleSeconds));
hopper.setRetractInterlock(
intake::isStowed,
() -> intake.getStopCommand().withTimeout(IntakeConstants.kInterlockSettleSeconds));
}

configureControlPanelBindings();
configureAutoOptions();
Expand Down Expand Up @@ -340,15 +343,15 @@ public Robot() {
/** This function is called periodically during all modes. */
@Override
public void robotPeriodic() {
long loopStart = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long loopStart = FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;

// Runs the Scheduler. This is responsible for polling buttons, adding
// newly-scheduled commands, running already-scheduled commands, removing
// finished or interrupted commands, and running subsystem periodic() methods.
// This must be called from the robot's periodic block in order for anything in
// the Command-based framework to work.
CommandScheduler.getInstance().run();
long t1 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t1 = FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;

logCANBus("CAN2", Constants.CANBusPorts.CAN2.bus);
logCANBus("CANHD", Constants.CANBusPorts.CANHD.bus);
Expand All @@ -359,16 +362,16 @@ public void robotPeriodic() {

Logger.recordOutput("USB/FreeSpaceMB", getUSBStorageFreeSpace() / 1024 / 1024);
GameState.logValues();
long t2 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t2 = FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;

// Publish kernel log events to NetworkTables (only runs on real robot)
if (RobotBase.isReal()) {
KernelLogMonitor.getInstance().publishToLogger();
}
long t3 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t3 = FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;

// Profiling output
if (Constants.PROFILING_ENABLED) {
if (FeatureFlags.PROFILING_ENABLED) {
long schedulerMs = (t1 - loopStart) / 1_000_000;
long gameStateMs = (t2 - t1) / 1_000_000;
long kernelMonitorMs = (t3 - t2) / 1_000_000;
Expand Down Expand Up @@ -414,7 +417,7 @@ public void disabledPeriodic() {
/** This function is called once when autonomous mode is enabled. */
@Override
public void autonomousInit() {
hopper.getRetractCommand().schedule();
if (hopper != null) hopper.getRetractCommand().schedule();
drive.setDefaultCommand(Commands.runOnce(drive::stop, drive).withName("Stop"));
autoSelector.scheduleAuto();
leds.clear();
Expand All @@ -430,7 +433,8 @@ public void autonomousPeriodic() {
/** This function is called once when teleop mode is enabled. */
@Override
public void teleopInit() {
if (!hopper.isDeployed() && !hopper.isStowed()) hopper.getRetractCommand().schedule();
if (hopper != null && !hopper.isDeployed() && !hopper.isStowed())
hopper.getRetractCommand().schedule();
autoSelector.cancelAuto();
ControllerSelector.getInstance().scan(true);
leds.clear();
Expand Down Expand Up @@ -549,13 +553,14 @@ public boolean getFieldRelativeInput() {
// Toggle hopper: deploy if stowed, stow if deployed (retracting intake first if needed).
// runOnce has no subsystem requirements so it always executes; the scheduled command
// requires hopper and will interrupt whatever is currently running on that subsystem.
zorroDriver
.DIn()
.onTrue(
Commands.runOnce(
() ->
(hopper.isDeployed() ? hopper.getRetractCommand() : hopper.getDeployCommand())
.schedule()));
if (FeatureFlags.kHopperEnabled)
zorroDriver
.DIn()
.onTrue(
Commands.runOnce(
() ->
(hopper.isDeployed() ? hopper.getRetractCommand() : hopper.getDeployCommand())
.schedule()));

// Desaturate turret and advance feeder
zorroDriver.AIn().whileTrue(createDesaturateAndShootCommand(controller));
Expand Down Expand Up @@ -857,7 +862,7 @@ private void logScheduler() {
logSubsystem("Vision", vision);
logSubsystem("Launcher", launcher);
logSubsystem("Feeder", feeder);
logSubsystem("Hopper", hopper);
if (hopper != null) logSubsystem("Hopper", hopper);
logSubsystem("Intake", intake);
logAlerts();
}
Expand Down
17 changes: 9 additions & 8 deletions src/main/java/frc/robot/subsystems/drive/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.Constants;
import frc.robot.Constants.FeatureFlags;
import frc.robot.Constants.Mode;
import frc.robot.util.LocalADStarAK;
import java.util.concurrent.locks.Lock;
Expand Down Expand Up @@ -155,18 +156,18 @@ public Drive(

@Override
public void periodic() {
long startNanos = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long startNanos = FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;

odometryLock.lock(); // Prevents odometry updates while reading data
long t1 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t1 = FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;
gyroIO.updateInputs(gyroInputs);
long t2 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t2 = FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;
Logger.processInputs("Drive/Gyro", gyroInputs);
long t3 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t3 = FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;
for (var module : modules) {
module.periodic();
}
long t4 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t4 = FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;
odometryLock.unlock();

// Stop moving when disabled
Expand All @@ -181,7 +182,7 @@ public void periodic() {
Logger.recordOutput("SwerveStates/Setpoints", emptyModuleStates);
Logger.recordOutput("SwerveStates/SetpointsOptimized", emptyModuleStates);
}
long t5 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t5 = FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;

// Update odometry
double[] sampleTimestamps =
Expand Down Expand Up @@ -215,15 +216,15 @@ public void periodic() {

chassisSpeeds = kinematics.toChassisSpeeds(getModuleStates());
}
long t6 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t6 = FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;

// Update gyro alert
boolean gyroDisconnected = !gyroInputs.connected && Constants.currentMode != Mode.SIM;
gyroDisconnectedAlert.set(gyroDisconnected);
Logger.recordOutput("Faults/Drive/GyroDisconnected", gyroDisconnected);

// Profiling output
if (Constants.PROFILING_ENABLED) {
if (FeatureFlags.PROFILING_ENABLED) {
long totalMs = (t6 - startNanos) / 1_000_000;
if (totalMs > 5) {
System.out.println(
Expand Down
12 changes: 6 additions & 6 deletions src/main/java/frc/robot/subsystems/drive/Module.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
import edu.wpi.first.wpilibj.Alert;
import edu.wpi.first.wpilibj.Alert.AlertType;
import edu.wpi.first.wpilibj.Preferences;
import frc.robot.Constants;
import frc.robot.Constants.FeatureFlags;
import org.littletonrobotics.junction.Logger;

public class Module {
Expand Down Expand Up @@ -56,11 +56,11 @@ public Module(ModuleIO io, int index) {
}

public void periodic() {
long t0 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t0 = FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;
io.updateInputs(inputs);
long t1 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t1 = FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;
Logger.processInputs("Drive/Module" + Integer.toString(index), inputs);
long t2 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t2 = FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;

// Calculate positions for odometry
int sampleCount = inputs.odometryTimestamps.length; // All signals are sampled together
Expand All @@ -76,10 +76,10 @@ public void periodic() {
turnDisconnectedAlert.set(!inputs.turnConnected);
Logger.recordOutput("Faults/Module" + index + "/DriveDisconnected", !inputs.driveConnected);
Logger.recordOutput("Faults/Module" + index + "/TurnDisconnected", !inputs.turnConnected);
long t3 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t3 = FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;

// Profiling output
if (Constants.PROFILING_ENABLED) {
if (FeatureFlags.PROFILING_ENABLED) {
long totalMs = (t3 - t0) / 1_000_000;
if (totalMs > 2) {
System.out.println(
Expand Down
12 changes: 6 additions & 6 deletions src/main/java/frc/robot/subsystems/feeder/Feeder.java
Original file line number Diff line number Diff line change
Expand Up @@ -29,24 +29,24 @@ public Feeder(SpindexerIO spindexerIO, KickerIO kickerIO) {

@Override
public void periodic() {
long t0 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t0 = Constants.FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;
spindexerIO.updateInputs(spindexerInputs);
long t1 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t1 = Constants.FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;
kickerIO.updateInputs(kickerInputs);
long t2 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t2 = Constants.FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;

Logger.processInputs("Spindexer", spindexerInputs);
long t3 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t3 = Constants.FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;
Logger.processInputs("Kicker", kickerInputs);
long t4 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t4 = Constants.FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;

spindexerDisconnectedAlert.set(!spindexerInputs.connected);
kickerDisconnectedAlert.set(!kickerInputs.connected);
Logger.recordOutput("Faults/Feeder/SpindexerDisconnected", !spindexerInputs.connected);
Logger.recordOutput("Faults/Feeder/KickerDisconnected", !kickerInputs.connected);

// Profiling output
if (Constants.PROFILING_ENABLED) {
if (Constants.FeatureFlags.PROFILING_ENABLED) {
long totalMs = (t4 - t0) / 1_000_000;
if (totalMs > 2) {
System.out.println(
Expand Down
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/subsystems/hopper/Hopper.java
Original file line number Diff line number Diff line change
Expand Up @@ -24,14 +24,14 @@ public Hopper(HopperIO hopperIO) {

@Override
public void periodic() {
long t0 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t0 = Constants.FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;
hopperIO.updateInputs(hopperInputs);
long t1 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t1 = Constants.FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;
Logger.processInputs("Hopper", hopperInputs);
long t2 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t2 = Constants.FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;

// Profiling output
if (Constants.PROFILING_ENABLED) {
if (Constants.FeatureFlags.PROFILING_ENABLED) {
long totalMs = (t2 - t0) / 1_000_000;
if (totalMs > 2) {
System.out.println(
Expand Down
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/subsystems/intake/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,24 +42,24 @@ public Intake(RollerIO upperRollerIO, RollerIO lowerRollerIO, IntakeArmIO intake

@Override
public void periodic() {
long t0 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t0 = Constants.FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;
upperRollerIO.updateInputs(upperRollerInputs);
lowerRollerIO.updateInputs(lowerRollerInputs);
intakeArmIO.updateInputs(intakeArmInputs);
long t1 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t1 = Constants.FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;

Logger.processInputs("UpperRoller", upperRollerInputs);
Logger.processInputs("LowerRoller", lowerRollerInputs);
Logger.processInputs("IntakeArm", intakeArmInputs);
long t2 = Constants.PROFILING_ENABLED ? System.nanoTime() : 0;
long t2 = Constants.FeatureFlags.PROFILING_ENABLED ? System.nanoTime() : 0;

upperRollerDisconnectedAlert.set(!upperRollerInputs.connected);
lowerRollerDisconnectedAlert.set(!lowerRollerInputs.connected);
Logger.recordOutput("Faults/Intake/UpperRollerDisconnected", !upperRollerInputs.connected);
Logger.recordOutput("Faults/Intake/LowerRollerDisconnected", !lowerRollerInputs.connected);

// Profiling output
if (Constants.PROFILING_ENABLED) {
if (Constants.FeatureFlags.PROFILING_ENABLED) {
long totalMs = (t2 - t0) / 1_000_000;
if (totalMs > 2) {
System.out.println(
Expand Down
Loading
Loading