Skip to content
This repository has been archived by the owner on Jan 9, 2025. It is now read-only.

Commit

Permalink
clean pivot shooter, also note shooter kinda needs to be retuned (fly…
Browse files Browse the repository at this point in the history
…wheels and the pivot shooter)
  • Loading branch information
chaoticthegreat committed Nov 7, 2024
1 parent 58dfd10 commit 71b85c0
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 22 deletions.
15 changes: 0 additions & 15 deletions src/main/java/frc/robot/subsystems/pivotshooter/PivotShooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@
import com.ctre.phoenix6.SignalLogger;
import edu.wpi.first.math.interpolation.InterpolatingDoubleTreeMap;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.subsystems.vision.Vision;
import frc.robot.utils.DisableSubsystem;
Expand Down Expand Up @@ -76,25 +75,11 @@ public Command off() {
return this.runOnce(pivotShooterIO::off);
}

public Command slamZero() {
return this.run(() -> pivotShooterIO.setVoltage(PivotShooterConstants.kPivotSlamShooterVoltage))
.until(
() ->
pivotShooterIOAutoLogged.pivotShooterMotorStatorCurrent
> PivotShooterConstants.kPivotSlamStallCurrent)
.andThen(this.zero());
}

public Command setSub() {
return setPosition(
PivotShooterConstants.kSubWooferPreset * PivotShooterConstants.kPivotMotorGearing);
}

public Command slamAndPID() {

return Commands.sequence(this.setPosition(0), this.slamZero());
}

public Command zero() {
return this.runOnce(pivotShooterIO::zero);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,21 +22,16 @@ public final class PivotShooterConstants {

public static final int kPivotMotorID = 51;

/* PID */

/* Physics/geometry */
public static final double kPivotMotorGearing = 138.333; // 22 by 1
public static final double kPivotMotorGearing = 138.333; // TODO: get from nate

/* Preset */
public static final double kPivotSlamIntakeVoltage = -5;
public static final double kPivotSlamShooterVoltage = -2;
// max value is 8, min is 0

/* Misc */
public static final boolean kUseFOC = false;
public static final boolean kUseMotionMagic = false; // idk
public static final double updateFrequency = 50.0;
public static final int flashConfigRetries = 5;
public static final double kPivotSlamStallCurrent = 50;

public static final TalonFXConfiguration motorConfigs =
new TalonFXConfiguration()
Expand Down

0 comments on commit 71b85c0

Please sign in to comment.