Skip to content

Commit

Permalink
Rename subsystems and switch to non async queue
Browse files Browse the repository at this point in the history
  • Loading branch information
camearle20 committed Jan 13, 2024
1 parent e60c3ee commit b0826d1
Show file tree
Hide file tree
Showing 12 changed files with 49 additions and 48 deletions.
1 change: 1 addition & 0 deletions build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -151,6 +151,7 @@ spotless {
toggleOffOn()
googleJavaFormat()
removeUnusedImports()
indentWithSpaces(4)
trimTrailingWhitespace()
endWithNewline()
}
Expand Down
Empty file modified gradlew
100644 → 100755
Empty file.
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ public RobotContainer() {
// new ModuleIOTalonFX(1),
// new ModuleIOTalonFX(2),
// new ModuleIOTalonFX(3));
shooter = new KitbotShooter(new FlywheelIOSparkMax(), new FeederIOSparkMax());
shooter = new KitbotShooter(new KitbotFlywheelIOSparkMax(), new KitbotFeederIOSparkMax());
break;

case SIM:
Expand All @@ -82,7 +82,7 @@ public RobotContainer() {
new ModuleIOSim(),
new ModuleIOSim(),
new ModuleIOSim());
shooter = new KitbotShooter(new FlywheelIOSim(), new FeederIOSim());
shooter = new KitbotShooter(new KitbotFlywheelIOSim(), new KitbotFeederIOSim());
break;

default:
Expand All @@ -94,7 +94,7 @@ public RobotContainer() {
new ModuleIO() {},
new ModuleIO() {},
new ModuleIO() {});
shooter = new KitbotShooter(new FlywheelIO() {}, new FeederIO() {});
shooter = new KitbotShooter(new KitbotFlywheelIO() {}, new KitbotFeederIO() {});
break;
}

Expand All @@ -116,7 +116,7 @@ public RobotContainer() {
"Flywheel FF Characterization",
Commands.sequence(
Commands.runOnce(
() -> shooter.setCurrentMode(KitbotShooter.MODE.CHARACTERIZING), shooter),
() -> shooter.setCurrentMode(KitbotShooter.Mode.CHARACTERIZING), shooter),
new FeedForwardCharacterization(
shooter, shooter::runFlywheelVolts, shooter::getFlywheelVelocityRadPerSec),
Commands.runOnce(() -> shooter.setCurrentMode(null))));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,10 @@
import com.ctre.phoenix6.CANBus;
import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.hardware.ParentDevice;
import java.util.ArrayDeque;
import java.util.ArrayList;
import java.util.List;
import java.util.Queue;
import java.util.concurrent.ArrayBlockingQueue;
import java.util.concurrent.locks.Lock;
import java.util.concurrent.locks.ReentrantLock;

Expand Down Expand Up @@ -55,7 +55,7 @@ private PhoenixOdometryThread() {
}

public Queue<Double> registerSignal(ParentDevice device, StatusSignal<Double> signal) {
Queue<Double> queue = new ArrayBlockingQueue<>(100);
Queue<Double> queue = new ArrayDeque<>(100);
signalsLock.lock();
Drive.odometryLock.lock();
try {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,10 +14,10 @@
package frc.robot.subsystems.drive;

import edu.wpi.first.wpilibj.Notifier;
import java.util.ArrayDeque;
import java.util.ArrayList;
import java.util.List;
import java.util.Queue;
import java.util.concurrent.ArrayBlockingQueue;
import java.util.function.DoubleSupplier;

/**
Expand Down Expand Up @@ -47,7 +47,7 @@ private SparkMaxOdometryThread() {
}

public Queue<Double> registerSignal(DoubleSupplier signal) {
Queue<Double> queue = new ArrayBlockingQueue<>(100);
Queue<Double> queue = new ArrayDeque<>(100);
Drive.odometryLock.lock();
try {
signals.add(signal);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

import org.littletonrobotics.junction.AutoLog;

public interface FeederIO {
public interface KitbotFeederIO {
@AutoLog
class FeederIOInputs {
public double feederPositionRads = 0.0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
import edu.wpi.first.wpilibj.simulation.FlywheelSim;
import frc.robot.Constants;

public class FeederIOSim implements FeederIO {
public class KitbotFeederIOSim implements KitbotFeederIO {
private FlywheelSim sim = new FlywheelSim(DCMotor.getNeoVortex(1), (1.0 / 1.0), 0.002);

private double positionRads;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,13 +7,13 @@
import edu.wpi.first.math.util.Units;
import frc.robot.Constants;

public class FeederIOSparkMax implements FeederIO {
public class KitbotFeederIOSparkMax implements KitbotFeederIO {
private static final double GEARING = (1.0 / 1.0);

private final CANSparkMax motor;
private final RelativeEncoder encoder;

public FeederIOSparkMax() {
public KitbotFeederIOSparkMax() {
motor = new CANSparkMax(3, CANSparkLowLevel.MotorType.kBrushless);

motor.restoreFactoryDefaults();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

import org.littletonrobotics.junction.AutoLog;

public interface FlywheelIO {
public interface KitbotFlywheelIO {
@AutoLog
class FlywheelIOInputs {
public double[] flywheelPositionRads = new double[] {};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
import frc.robot.Constants;
import java.util.Arrays;

public class FlywheelIOSim implements FlywheelIO {
public class KitbotFlywheelIOSim implements KitbotFlywheelIO {
private static final SimpleMotorFeedforward ffModel = new SimpleMotorFeedforward(0.0, 0.0, 0.0);
private static final PIDController feedback = new PIDController(0.0, 0.0, 0.0);

Expand All @@ -22,7 +22,7 @@ public class FlywheelIOSim implements FlywheelIO {
public void updateInputs(FlywheelIOInputs inputs) {
positionRads += sim.getAngularVelocityRadPerSec() * (Constants.loopPeriodMs / 1000.0);
inputs.flywheelPositionRads = new double[] {positionRads, positionRads};
inputs.flywheelPositionRads = new double[2];
inputs.flywheelVelocityRadPerSec = new double[2];
Arrays.fill(inputs.flywheelPositionRads, sim.getAngularVelocityRadPerSec());
inputs.flywheelAppliedVolts = new double[] {inputVolts, inputVolts};
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
import frc.robot.Constants;
import java.util.Arrays;

public class FlywheelIOSparkMax implements FlywheelIO {
public class KitbotFlywheelIOSparkMax implements KitbotFlywheelIO {
// FIND THESE CONSTANTS
private static final boolean masterInverted = false;
private static final boolean followerInverted = false;
Expand All @@ -21,7 +21,7 @@ public class FlywheelIOSparkMax implements FlywheelIO {
private final CANSparkMax leader, follower;
private final RelativeEncoder masterEncoder, followerEncoder;

public FlywheelIOSparkMax() {
public KitbotFlywheelIOSparkMax() {
// FIND ID
leader = new CANSparkMax(0, CANSparkLowLevel.MotorType.kBrushless);
follower = new CANSparkMax(1, CANSparkLowLevel.MotorType.kBrushless);
Expand Down
62 changes: 31 additions & 31 deletions src/main/java/frc/robot/subsystems/kitbotshooter/KitbotShooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,69 +13,69 @@ public class KitbotShooter extends SubsystemBase {
private static double flywheelIntakeVoltage = -5.0;
private static double feederIntakeVoltage = -5.0;

private FlywheelIO flywheelIO;
private FeederIO feederIO;
private KitbotFlywheelIO kitbotFlywheelIO;
private KitbotFeederIO kitbotFeederIO;

private FlywheelIOInputsAutoLogged flywheelInputs = new FlywheelIOInputsAutoLogged();
private FeederIOInputsAutoLogged feederInputs = new FeederIOInputsAutoLogged();

private MODE currentMode = null;
private Mode currentMode = null;

public KitbotShooter(FlywheelIO flywheelIO, FeederIO feederIO) {
this.flywheelIO = flywheelIO;
this.feederIO = feederIO;
public KitbotShooter(KitbotFlywheelIO kitbotFlywheelIO, KitbotFeederIO kitbotFeederIO) {
this.kitbotFlywheelIO = kitbotFlywheelIO;
this.kitbotFeederIO = kitbotFeederIO;
}

@Override
public void periodic() {
// update inputs
flywheelIO.updateInputs(flywheelInputs);
feederIO.updateInputs(feederInputs);
kitbotFlywheelIO.updateInputs(flywheelInputs);
kitbotFeederIO.updateInputs(feederInputs);
// process inputs
Logger.processInputs("KitbotShooter/Flywheel", flywheelInputs);
Logger.processInputs("KitbotShooter/Feeder", feederInputs);

// check for current mode
if (currentMode == null) {
currentMode = DriverStation.isEnabled() ? MODE.ENABLED : MODE.DISABLED;
flywheelIO.setBrakeMode(DriverStation.isEnabled());
feederIO.setBrakeMode(DriverStation.isEnabled());
currentMode = DriverStation.isEnabled() ? Mode.ENABLED : Mode.DISABLED;
kitbotFlywheelIO.setBrakeMode(DriverStation.isEnabled());
kitbotFeederIO.setBrakeMode(DriverStation.isEnabled());
}

if (currentMode == MODE.DISABLED) {
flywheelIO.setBrakeMode(false);
feederIO.setBrakeMode(false);
} else if (currentMode == MODE.ENABLED) {
if (currentMode == Mode.DISABLED) {
kitbotFlywheelIO.setBrakeMode(false);
kitbotFeederIO.setBrakeMode(false);
} else if (currentMode == Mode.ENABLED) {
// other stuff
} else if (currentMode == MODE.CHARACTERIZING) {
} else if (currentMode == Mode.CHARACTERIZING) {

}
}

/** Set input voltage for flywheel */
public void runFlywheelVolts(double volts) {
flywheelIO.runVolts(volts);
kitbotFlywheelIO.runVolts(volts);
}

/** Set input voltage for feeder */
public void runFeederVolts(double volts) {
feederIO.runVolts(volts);
kitbotFeederIO.runVolts(volts);
}

/** Run flywheel at velocity */
public void runFlywheelVelocity(double rpm) {
if (currentMode != MODE.ENABLED) return;
if (currentMode != Mode.ENABLED) return;
double rps = Units.rotationsPerMinuteToRadiansPerSecond(rpm);
flywheelIO.runVelocity(Units.rotationsToRadians(rps));
kitbotFlywheelIO.runVelocity(Units.rotationsToRadians(rps));
}

public void setCurrentMode(MODE mode) {
public void setCurrentMode(Mode mode) {
currentMode = mode;
}

@AutoLogOutput(key = "KitbotShooter/FlywheelRPM")
public double getFlywheelRPM() {
return flywheelIO.getVelocityRPM();
return kitbotFlywheelIO.getVelocityRPM();
}

@AutoLogOutput(key = "KitbotShooter/FlywheelVelocityRadPerSec")
Expand All @@ -95,17 +95,17 @@ public double getFeederCurrent() {

public Command intakeCommand() {
return Commands.startEnd(
() -> {
flywheelIO.runVolts(flywheelIntakeVoltage);
feederIO.runVolts(feederIntakeVoltage);
},
() -> {
flywheelIO.runVolts(0.0);
feederIO.runVolts(0.0);
});
() -> {
kitbotFlywheelIO.runVolts(flywheelIntakeVoltage);
kitbotFeederIO.runVolts(feederIntakeVoltage);
},
() -> {
kitbotFlywheelIO.runVolts(0.0);
kitbotFeederIO.runVolts(0.0);
});
}

public enum MODE {
public enum Mode {
ENABLED,
DISABLED,
CHARACTERIZING;
Expand Down

0 comments on commit b0826d1

Please sign in to comment.