Skip to content
This repository was archived by the owner on Jan 9, 2025. It is now read-only.
Open
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
30 changes: 17 additions & 13 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,28 +31,27 @@
import frc.robot.subsystems.ampevator.AmpevatorIOTalonFX;
import frc.robot.subsystems.ampevatorrollers.Roller;
import frc.robot.subsystems.ampevatorrollers.RollerConstants;
import frc.robot.subsystems.ampevatorrollers.RollerIOTalonFX;
import frc.robot.subsystems.climb.Climb;
import frc.robot.subsystems.climb.ClimbIOTalonFX;
import frc.robot.subsystems.climb.ClimbConstants;
import frc.robot.subsystems.intake.Intake;
import frc.robot.subsystems.intake.IntakeConstants;
import frc.robot.subsystems.pivotshooter.PivotShooter;
import frc.robot.subsystems.pivotshooter.PivotShooterConstants;
import frc.robot.subsystems.pivotshooter.PivotShooterIOSim;
import frc.robot.subsystems.pivotshooter.PivotShooterIOTalonFX;
import frc.robot.subsystems.shooter.Shooter;
import frc.robot.subsystems.shooter.ShooterIOSim;
import frc.robot.subsystems.shooter.ShooterIOTalonFX;
import frc.robot.subsystems.spindex.ShooterFeederIOTalonFX;
import frc.robot.subsystems.spindex.BaseSpindexConstants;
import frc.robot.subsystems.spindex.Spindex;
import frc.robot.subsystems.spindex.SpindexConstants;
import frc.robot.subsystems.spindex.SpindexIOTalonFX;
import frc.robot.subsystems.spindex.SpindexFeederConstants;
import frc.robot.subsystems.swerve.*;
import frc.robot.subsystems.turret.*;
import frc.robot.subsystems.vision.Vision;
import frc.robot.subsystems.vision.VisionIOLimelight;
import frc.robot.utils.MappedXboxController;
import frc.robot.utils.NamedCommands;
import frc.robot.utils.generics.SingleMotorSubsystemIOTalonFX;
import frc.robot.utils.generics.VelocityIOTalonFX;

/**
* This class is where the bulk of the robot should be declared. Since Command-based is a
Expand Down Expand Up @@ -83,26 +82,31 @@ public class RobotContainer {
private final PivotShooter pivotShooter =
new PivotShooter(
Constants.FeatureFlags.kPivotShooterEnabled,
Utils.isSimulation() ? new PivotShooterIOSim() : new PivotShooterIOTalonFX());
Utils.isSimulation()
? new PivotShooterIOSim()
: new SingleMotorSubsystemIOTalonFX<PivotShooterConstants>());

private final Roller ampevatorRollers =
new Roller(
Constants.FeatureFlags.kAmpevatorRollersEnabled,
new RollerIOTalonFX(),
new SingleMotorSubsystemIOTalonFX<RollerConstants>(),
new BeamBreakIOBanner(RollerConstants.kRollerBeamBreakDIO));

private final Climb climb = new Climb(Constants.FeatureFlags.kClimbEnabled, new ClimbIOTalonFX());
private final Climb climb =
new Climb(
Constants.FeatureFlags.kClimbEnabled,
new SingleMotorSubsystemIOTalonFX<ClimbConstants>());
private final Intake intake =
new Intake(
Constants.FeatureFlags.kIntakeEnabled,
new SingleMotorSubsystemIOTalonFX<IntakeConstants>(),
new VelocityIOTalonFX<IntakeConstants>(),
new BeamBreakIOBanner(IntakeConstants.kIntakeBeamBreakDIO));
private final Spindex spindex =
new Spindex(
Constants.FeatureFlags.kSpindexEnabled,
new SpindexIOTalonFX(),
new ShooterFeederIOTalonFX(),
new BeamBreakIOBanner(SpindexConstants.kSpindexBeamBreakDIO));
new SingleMotorSubsystemIOTalonFX<SpindexConstants>(),
new SingleMotorSubsystemIOTalonFX<SpindexFeederConstants>(),
new BeamBreakIOBanner(BaseSpindexConstants.kSpindexBeamBreakDIO));
private final Vision vision = new Vision(new VisionIOLimelight());

private final Superstructure superstructure =
Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/subsystems/Superstructure.java
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,8 @@ public void configStateTransitions() {
.onTrue(spindex.goToShooter())
.onTrue(
pivotShooter.setPosition(
PivotShooterConstants.kSubWooferPreset * PivotShooterConstants.kPivotMotorGearing))
PivotShooterConstants.kSubWooferPreset
* PivotShooterConstants.SimulationConstants.kGearRatio))
.onTrue(
shooter.setVelocity(
ShooterConstants.kShooterSpeakerRPS, ShooterConstants.kShooterFollowerSpeakerRPS))
Expand Down
21 changes: 12 additions & 9 deletions src/main/java/frc/robot/subsystems/ampevatorrollers/Roller.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,11 +17,14 @@
import frc.robot.subsystems.BeamBreakIO;
import frc.robot.subsystems.BeamBreakIOInputsAutoLogged;
import frc.robot.utils.DisableSubsystem;
import frc.robot.utils.generics.SingleMotorSubsystemIO;
import frc.robot.utils.generics.SingleMotorSubsystemInputsAutoLogged;
import org.littletonrobotics.junction.Logger;

public class Roller extends DisableSubsystem {
private final RollerIO rollerIO;
private final RollerIOInputsAutoLogged rollerIOAutoLogged = new RollerIOInputsAutoLogged();
private final SingleMotorSubsystemIO rollerIO;
private final SingleMotorSubsystemInputsAutoLogged rollerIOAutoLogged =
new SingleMotorSubsystemInputsAutoLogged();

private final BeamBreakIO beamBreakIO;
private final BeamBreakIOInputsAutoLogged beamBreakIOAutoLogged =
Expand All @@ -32,7 +35,7 @@ public class Roller extends DisableSubsystem {
public final Trigger debouncedBeamBreak = new Trigger(this::isBeamBroken).debounce(0.1);
;

public Roller(boolean disabled, RollerIO rollerIO, BeamBreakIO beamBreakIO) {
public Roller(boolean disabled, SingleMotorSubsystemIO rollerIO, BeamBreakIO beamBreakIO) {
super(disabled);

this.rollerIO = rollerIO;
Expand All @@ -48,8 +51,8 @@ public Roller(boolean disabled, RollerIO rollerIO, BeamBreakIO beamBreakIO) {
new SysIdRoutine.Mechanism(
(volts) ->
rollerIO
.getRollerMotor()
.setControl(rollerIO.getRollerVoltageRequest().withOutput(volts.in(Volts))),
.getMotor()
.setControl(rollerIO.getVoltageRequest().withOutput(volts.in(Volts))),
null,
this));
}
Expand All @@ -64,25 +67,25 @@ public void periodic() {
}

public Command setVoltage(double voltage) {
return this.run(() -> rollerIO.setRollerVoltage(voltage)).finallyDo(rollerIO::off);
return this.run(() -> rollerIO.setVoltage(voltage)).finallyDo(rollerIO::off);
}

public Command setVelocity(double velocity, double passthroughVelocity) {
return this.run(() -> rollerIO.setRollerVelocity(velocity)).finallyDo(rollerIO::off);
return this.run(() -> rollerIO.setVelocity(velocity)).finallyDo(rollerIO::off);
}

public Command off() {
return this.runOnce(rollerIO::off);
}

public Command intakeNote() {
return this.run(() -> rollerIO.setRollerVoltage(RollerConstants.kRollerIntakeVoltage))
return this.run(() -> rollerIO.setVoltage(RollerConstants.kRollerIntakeVoltage))
.until(debouncedBeamBreak)
.finallyDo(rollerIO::off);
}

public Command outtake() {
return this.run(() -> rollerIO.setRollerVoltage(RollerConstants.kRollerOuttakeVoltage))
return this.run(() -> rollerIO.setVoltage(RollerConstants.kRollerOuttakeVoltage))
.until(debouncedBeamBreak)
.finallyDo(rollerIO::off);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,22 +10,12 @@
import com.ctre.phoenix6.configs.*;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import frc.robot.utils.generics.SingleMotorConstants;

public final class RollerConstants {
public final class RollerConstants implements SingleMotorConstants {
/* CAN */
public static final int kRollerMotorID = 33;

public static final double kRollerOuttakeVoltage = 12;

// Time of Flight constants
public static final double kBeamBreakDelayTime = 0;

public static final int kRollerBeamBreakDIO = 2;

public static double updateFrequency = 50;
public static boolean kRollerMotionMagic = false;

public static final TalonFXConfiguration motorConfigs =
public static final int kMotorID = 33;
public static final TalonFXConfiguration kMotorConfig =
new TalonFXConfiguration()
.withSlot0(new Slot0Configs().withKS(0).withKV(0.1).withKP(1).withKI(0).withKD(0))
.withMotorOutput(
Expand All @@ -41,6 +31,20 @@ public final class RollerConstants {
new CurrentLimitsConfigs()
.withStatorCurrentLimitEnable(true)
.withStatorCurrentLimit(80));
public static int flashConfigRetries = 5;

public static final boolean kUseMotionMagic = false;
public static final boolean kUseFOC = true;
public static final double kStatusSignalUpdateFrequency = 50.0; // Hz
public static final int kFlashConfigRetries = 5;

// Time of Flight constants
public static final double kBeamBreakDelayTime = 0;
public static final int kRollerBeamBreakDIO = 2;
// Presets
public static final double kRollerOuttakeVoltage = 12;
public static double kRollerIntakeVoltage = 4;

public static class SimulationConstants {
public static final double kGearRatio = 1.0; // todo: tune
}
}
40 changes: 0 additions & 40 deletions src/main/java/frc/robot/subsystems/ampevatorrollers/RollerIO.java

This file was deleted.

This file was deleted.

12 changes: 8 additions & 4 deletions src/main/java/frc/robot/subsystems/climb/Climb.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,15 +14,18 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.utils.DisableSubsystem;
import frc.robot.utils.generics.SingleMotorSubsystemIO;
import frc.robot.utils.generics.SingleMotorSubsystemInputsAutoLogged;
import org.littletonrobotics.junction.Logger;

public class Climb extends DisableSubsystem {

private final ClimbIO climbIO;
private final ClimbIOInputsAutoLogged climbIOAutoLogged = new ClimbIOInputsAutoLogged();
private final SingleMotorSubsystemIO climbIO;
private final SingleMotorSubsystemInputsAutoLogged climbIOAutoLogged =
new SingleMotorSubsystemInputsAutoLogged();
private final SysIdRoutine m_sysIdRoutine;

public Climb(boolean disabled, ClimbIO climbIO) {
public Climb(boolean disabled, SingleMotorSubsystemIO climbIO) {
super(disabled);
this.climbIO = climbIO;
m_sysIdRoutine =
Expand Down Expand Up @@ -50,7 +53,8 @@ public void periodic() {
}

public Command setPosition(double position) {
return this.run(() -> climbIO.setPosition(position * ClimbConstants.gearRatio));
return this.run(
() -> climbIO.setPosition(position * ClimbConstants.SimulationConstants.kGearRatio));
}

public Command setVoltage(double voltage) {
Expand Down
Loading