Skip to content
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
7 changes: 6 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -408,7 +408,8 @@ public void putShuffleboardCommands() {
new RunHopperAndFeeder(hopperSubsystem, feederSubsystem));
SmartDashboard.putData("RunTurret",
new TestSetTurretAngle(turretSubsystem));

SmartDashboard.putData("Run \"ShootButton\"",
new ShootButton(controllerSubsystem));
SmartDashboard.putData(
"test/Run Dashboard Shot Test (30s)",
new RunDashboardShotTest(anglerSubsystem, turretSubsystem, shooterSubsystem));
Expand Down Expand Up @@ -591,4 +592,8 @@ public ShootingState getShootingState() {
public IntakeDeployerSubsystem getDeployer(){
return intakeDeployer;
}

public ShooterSubsystem getShooterSubsystem(){
return shooterSubsystem;
}
}
3 changes: 3 additions & 0 deletions src/main/java/frc/robot/constants/GameConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,9 @@ public enum Mode {
public static final int STEER_JOYSTICK_PORT = 1;
public static final int XBOX_CONTROLLER_PORT = 2;

// Thresholds
public static final double SHOOTER_THRESHOLD = 1500;

//Speeds
public static final double ROLLER_SPEED = 0.25;
public static final double TILT_SPEED = -0.5; // Arm motor is inverted - use negative speed
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -243,7 +243,9 @@ public boolean shouldFeederSpin() {
}

public boolean shouldHopperSpin() {
return activeTargets.hopperSpin;
return activeTargets.hopperSpin
&& Math.abs(robotContainer.getShooterSubsystem().getVelocity()) > Math.abs(Constants.SHOOTER_THRESHOLD)
&& Math.abs(activeTargets.shooterVelocityRpm) > Math.abs(Constants.SHOOTER_THRESHOLD);
}

public void setDriverActivatedShooting(boolean set) {
Expand Down
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -108,4 +108,8 @@ public static MotorPair createMotor() {
}
public record MotorPair(SparkMaxPidMotor mainMotor, SparkMax followerMotor){}
public record MotorPairIO(RealSparkMaxIo mainMotor, RealSparkMaxIo followerMotor){}

public double getVelocity() {
return io.getEncoderVelocity();
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,11 @@ public MockSparkMaxIo(String name, MotorLoggableInputs inputs) {
public void set(double speed) {
}

@Override
public double getEncoderVelocity() {
return 0; // example
}

@Override
public void setVoltage(double voltage) {
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,12 @@ public boolean isFwdSwitchPressed() {
public boolean isRevSwitchPressed() {
return getInputs().getRevLimit();
}


@Override
public double getEncoderVelocity() {
return getInputs().getEncoderVelocity();
}

@Override
protected void updateInputs(MotorLoggableInputs inputs) {
inputs.fromHardware(motor);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,8 @@
public interface SparkMaxIo extends BaseIo {
void set(double speed);

double getEncoderVelocity();

void setVoltage(double voltage);

void stopMotor();
Expand Down