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

Commit 00378c3

Browse files
committedNov 6, 2024··
cleanup
1 parent 16f399e commit 00378c3

File tree

6 files changed

+25
-45
lines changed

6 files changed

+25
-45
lines changed
 

‎scripts/map.json

+1-1
Original file line numberDiff line numberDiff line change
@@ -1 +1 @@
1-
{"driver":{"b":"shoot","x":"pivot shooter no","y":"reset heading","leftTrigger":"Slow Drive"},"operator":{"rightStick":"Turret"}}
1+
{"driver":{"y":"reset heading","leftTrigger":"Slow Drive"},"operator":{"a":"feed","x":"sub","y":"zero","rightBumper":"Intake"}}

‎src/main/java/frc/robot/RobotContainer.java

+14-12
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,6 @@
2424
import frc.robot.commands.AutoRoutines;
2525
import frc.robot.sim.SimMechs;
2626
import frc.robot.subsystems.BeamBreakIOAdafruit;
27-
import frc.robot.subsystems.Superstructure;
2827
import frc.robot.subsystems.ampevator.Ampevator;
2928
import frc.robot.subsystems.ampevator.AmpevatorIOSim;
3029
import frc.robot.subsystems.ampevator.AmpevatorIOTalonFX;
@@ -106,17 +105,17 @@ public class RobotContainer {
106105
new BeamBreakIOAdafruit(SpindexConstants.kSpindexBeamBreakDIO));
107106
private final Vision vision = new Vision(new VisionIOLimelight());
108107

109-
private final Superstructure superstructure =
110-
new Superstructure(
111-
ampevator,
112-
ampevatorRollers,
113-
turret,
114-
climb,
115-
intake,
116-
spindex,
117-
pivotShooter,
118-
shooter,
119-
vision);
108+
// private final Superstructure superstructure =
109+
// new Superstructure(
110+
// ampevator,
111+
// ampevatorRollers,
112+
// turret,
113+
// climb,
114+
// intake,
115+
// spindex,
116+
// pivotShooter,
117+
// shooter,
118+
// vision);
120119

121120
// Replace with CommandPS4Controller or CommandJoystick if needed
122121
public final MappedXboxController m_driverController =
@@ -160,6 +159,9 @@ private void configureBindings() {
160159
.onTrue(
161160
shooter.setVelocity(
162161
ShooterConstants.kShooterSpeakerRPS, ShooterConstants.kShooterSpeakerRPS));
162+
m_operatorController.a("feed").onTrue(spindex.feedNoteToShooter());
163+
m_operatorController.x("sub").onTrue(pivotShooter.setSub());
164+
m_operatorController.y("zero").onTrue(pivotShooter.setPosition(0));
163165
}
164166

165167
private void configureAutoChooser() {

‎src/main/java/frc/robot/subsystems/intake/IntakeConstants.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -42,5 +42,5 @@ public final class IntakeConstants {
4242
.withStatorCurrentLimitEnable(true)
4343
.withStatorCurrentLimit(80));
4444
public static int flashConfigRetries = 5;
45-
public static double kIntakeRedirectVoltage = -2;
45+
public static double kIntakeRedirectVoltage = 5;
4646
}

‎src/main/java/frc/robot/subsystems/pivotshooter/PivotShooter.java

+5
Original file line numberDiff line numberDiff line change
@@ -85,6 +85,11 @@ public Command slamZero() {
8585
.andThen(this.zero());
8686
}
8787

88+
public Command setSub() {
89+
return setPosition(
90+
PivotShooterConstants.kSubWooferPreset * PivotShooterConstants.kPivotMotorGearing);
91+
}
92+
8893
public Command slamAndPID() {
8994

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

‎src/main/java/frc/robot/subsystems/pivotshooter/PivotShooterConstants.java

-29
Original file line numberDiff line numberDiff line change
@@ -12,61 +12,32 @@
1212
import com.ctre.phoenix6.signals.InvertedValue;
1313
import com.ctre.phoenix6.signals.NeutralModeValue;
1414
import edu.wpi.first.math.geometry.Rotation2d;
15-
import edu.wpi.first.math.trajectory.TrapezoidProfile;
1615
import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim;
1716

1817
public final class PivotShooterConstants {
1918
// public static final double kSubWooferPreset = (3.5 + 0.3) / 138.33; // idk if
2019
// this works
2120
public static final double kSubWooferPreset = 3.4 / 138.33; // 3.2
2221
public static final double kFeederPreset = 5.9 / 138.33;
23-
public static final double kAmpPreset = (4) / 138.33;
24-
public static final double kWingNoteCenterPreset = 5.8 / 138.33;
25-
public static final double kWingNoteSidePreset =
26-
5.5 / 138.33; // old value: 5.7 distance: -1.5 //old ish?: 5.4
27-
public static final double kWingNoteFarSidePreset = 0 / 138.33;
28-
public static final double kTrussSourceSidePreset = 6.7 / 138.33; // -10.6875
29-
public static final double kHalfWingPodiumPreset =
30-
6.55 / 138.33; // old value: 6.7 distance: -11.5275
31-
public static final double kPodiumLeftPreset = 6.5 / 138.33;
32-
public static final double kPodiumRPreset = 6 / 138.33;
3322

3423
public static final int kPivotMotorID = 60;
3524

3625
/* PID */
37-
public static final TrapezoidProfile.Constraints kPivotProfileContraints =
38-
new TrapezoidProfile.Constraints(16, 16);
39-
40-
/* Tolerance/threshold */
41-
public static final double kPivotPositionToleranceDeg = 0.1; // 5deg for the pivot.
42-
public static final double kStallVelocityThreshold = 0.1;
4326

4427
/* Physics/geometry */
4528
public static final double kPivotMotorGearing = 138.333; // 22 by 1
46-
public static final double kPivotLength = 0.2;
47-
public static final double kPivotMinAngleDeg = -90;
48-
public static final double kPivotMaxAngleDeg = 50;
49-
public static final double kPivotStartingAngleDeg = 0;
50-
public static final double jKgMetersSquared = 0.1; // for sim
5129

5230
/* Preset */
5331
public static final double kPivotSlamIntakeVoltage = -5;
5432
public static final double kPivotSlamShooterVoltage = -2;
5533

5634
/* Misc */
57-
public static final int kNumPivotMotors = 1;
5835
public static final boolean kUseFOC = false;
5936
public static final boolean kUseMotionMagic = true; // idk
6037
public static final double updateFrequency = 50.0;
6138
public static final int flashConfigRetries = 5;
6239
public static final double kPivotSlamStallCurrent = 50;
6340

64-
public static final int kSpeakerAprilTagRed = 4;
65-
public static final int kSpeakerAprilTagBlue = 0;
66-
67-
public static final int kSpeakerBackupAprilTagRed = 5;
68-
public static final int kSpeakerBackupAprilTagBlue = 1;
69-
7041
public static final TalonFXConfiguration motorConfigs =
7142
new TalonFXConfiguration()
7243
.withSlot0(

‎src/main/java/frc/robot/subsystems/pivotshooter/PivotShooterIOTalonFX.java

+4-2
Original file line numberDiff line numberDiff line change
@@ -19,8 +19,10 @@
1919
public class PivotShooterIOTalonFX implements PivotShooterIO {
2020

2121
private final TalonFX pivotShooterMotor = new TalonFX(PivotShooterConstants.kPivotMotorID);
22-
private final PositionVoltage positionRequest = new PositionVoltage(0).withSlot(0);
23-
private final MotionMagicVoltage motionMagicRequest = new MotionMagicVoltage(0).withSlot(0);
22+
private final PositionVoltage positionRequest =
23+
new PositionVoltage(0).withSlot(0).withEnableFOC(PivotShooterConstants.kUseFOC);
24+
private final MotionMagicVoltage motionMagicRequest =
25+
new MotionMagicVoltage(0).withSlot(0).withEnableFOC(PivotShooterConstants.kUseFOC);
2426
private final VoltageOut voltageReq = new VoltageOut(0);
2527

2628
private final StatusSignal<Double> pivotShooterMotorVoltage = pivotShooterMotor.getMotorVoltage();

0 commit comments

Comments
 (0)
This repository has been archived.