Skip to content

Commit

Permalink
better consts and shooter better
Browse files Browse the repository at this point in the history
  • Loading branch information
indoorfish1 committed Oct 24, 2024
1 parent 3f9c4e9 commit 8c0e1bb
Show file tree
Hide file tree
Showing 5 changed files with 11 additions and 18 deletions.
5 changes: 3 additions & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -124,12 +124,13 @@ public static final class ShooterConstants {
public static final double kSHOOTER_GEAR_RATIO = 1.0;

public static final double kShooterRPM = 2500;
public static final double kDeliverRPM = 1000;
public static final double kReverseRPM = 400;

public static final double kCurrentLimit = 35; // amps

public static double kP = 1.5;

public static double kD;
public static double kD = 0.0;
}

public static final class AutoConstants {
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -315,7 +315,7 @@ private void configureButtonBindings() {
.whileTrue(
new ParallelCommandGroup(
new SequentialCommandGroup(new WaitCommand(1.5), intake.runDigestCommand()),
shooter.runShootCommand()));
new InstantCommand(() -> shooter.setShoot())));
driveController.leftTrigger(0.8).whileTrue(intake.runDigestCommand());
// driveController.rightTrigger(0.9).whileTrue(intake.runPoopCommand());
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/ShootCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,6 @@ public ShootCommand(Intake intake, Shooter shooter) {
new ParallelCommandGroup(
new SequentialCommandGroup(
new WaitCommand(1.0), new InstantCommand(() -> intake.runEatCommand())),
new InstantCommand(() -> shooter.runShootCommand()));
new InstantCommand(() -> shooter.setShoot()));
}
}
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/intake/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ public void periodic() {
case kStopped:
setpointRPMs = 0.0;
}

setpointRadPerSec = Units.rotationsPerMinuteToRadiansPerSecond(setpointRPMs);
controller.setSetpoint(setpointRadPerSec);
double voltage = ffModel.calculate(setpointRadPerSec);
Expand Down
18 changes: 5 additions & 13 deletions src/main/java/frc/robot/subsystems/shooter/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,8 @@
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
import frc.robot.Constants.ShooterConstants;
import frc.robot.util.LoggedTunableNumber;
import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;
Expand Down Expand Up @@ -48,12 +45,11 @@ public Shooter(ShooterIO io) {
io.setBrakeMode(false);

shootVelocity.initDefault(Constants.ShooterConstants.kShooterRPM);
deliverVelocity.initDefault(1000.0);
reverseVeloctiy.initDefault(-100.0);
deliverVelocity.initDefault(1000.0);
reverseVeloctiy.initDefault(Constants.ShooterConstants.kReverseRPM);
deliverVelocity.initDefault(Constants.ShooterConstants.kDeliverRPM);
spinDurationSec.initDefault(1.5);
kP.initDefault(ShooterConstants.kP);
kD.initDefault(ShooterConstants.kD);
kP.initDefault(Constants.ShooterConstants.kP);
kD.initDefault(Constants.ShooterConstants.kD);

// Switch constants based on mode (the physics simulator is treated as a
// separate robot with different tuning)
Expand Down Expand Up @@ -88,7 +84,7 @@ public void periodic() {
} else {
switch (mode) {
case kShoot:
setpoint = 4000;
setpoint = shootVelocity.get();
break;
case kDeliver:
setpoint = deliverVelocity.get();
Expand Down Expand Up @@ -140,8 +136,4 @@ public double getVoltageCommand() {
public double getActualVelocityRPMs() {
return inputs.velocityRPMs;
}

public Command runShootCommand() {
return new InstantCommand(() -> this.setShoot());
}
}

0 comments on commit 8c0e1bb

Please sign in to comment.