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

Commit ffb93bc

Browse files
add back superstruc
1 parent 2304b9c commit ffb93bc

File tree

9 files changed

+48
-54
lines changed

9 files changed

+48
-54
lines changed

scripts/map.json

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1 +1 @@
1-
{"driver":{"y":"reset heading","leftTrigger":"Slow Drive"},"operator":{"a":"feed","x":"sub","y":"zero","rightBumper":"Intake"}}
1+
{"driver":{"a":"Intake","y":"reset heading","leftTrigger":"Slow Drive"},"operator":{}}

simgui-ds.json

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,14 @@
11
{
2+
"Keyboard 0 Settings": {
3+
"window": {
4+
"visible": true
5+
}
6+
},
7+
"Keyboard 1 Settings": {
8+
"window": {
9+
"visible": true
10+
}
11+
},
212
"keyboardJoysticks": [
313
{
414
"axisConfig": [
@@ -92,6 +102,9 @@
92102
"robotJoysticks": [
93103
{
94104
"guid": "Keyboard0"
105+
},
106+
{
107+
"guid": "Keyboard1"
95108
}
96109
]
97110
}

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

Lines changed: 16 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@
2727
import frc.robot.commands.AutoRoutines;
2828
import frc.robot.sim.SimMechs;
2929
import frc.robot.subsystems.BeamBreakIOAdafruit;
30+
import frc.robot.subsystems.Superstructure;
3031
import frc.robot.subsystems.ampevator.Ampevator;
3132
import frc.robot.subsystems.ampevator.AmpevatorIOSim;
3233
import frc.robot.subsystems.ampevator.AmpevatorIOTalonFX;
@@ -109,18 +110,17 @@ public class RobotContainer {
109110
new BeamBreakIOAdafruit(SpindexConstants.kSpindexBeamBreakDIO));
110111
private final Vision vision = new Vision(new VisionIOLimelight());
111112

112-
// private final Superstructure superstructure = // TODO: when uncommented also uncomment the
113-
// periodic
114-
// new Superstructure(
115-
// ampevator,
116-
// ampevatorRollers,
117-
// turret,
118-
// climb,
119-
// intake,
120-
// spindex,
121-
// pivotShooter,
122-
// shooter,
123-
// vision);
113+
private final Superstructure superstructure =
114+
new Superstructure(
115+
ampevator,
116+
ampevatorRollers,
117+
turret,
118+
climb,
119+
intake,
120+
spindex,
121+
pivotShooter,
122+
shooter,
123+
vision);
124124

125125
// Replace with CommandPS4Controller or CommandJoystick if needed
126126
public final MappedXboxController m_driverController =
@@ -157,21 +157,14 @@ public RobotContainer() {
157157
* joysticks}.
158158
*/
159159
private void configureBindings() {
160-
m_operatorController
161-
.rightBumper("Intake")
162-
.whileTrue(
163-
intake
164-
.intakeIn()
165-
.alongWith(spindex.goToShooter())
166-
.alongWith(turret.setPosition(TurretConstants.kIntakePreset)));
160+
m_driverController
161+
.a("Intake")
162+
.onTrue(superstructure.setState(Superstructure.StructureState.INTAKE));
167163
m_operatorController
168164
.rightTrigger("Shooter")
169165
.onTrue(
170166
shooter.setVelocity(
171167
ShooterConstants.kShooterSpeakerRPS, ShooterConstants.kShooterFollowerSpeakerRPS));
172-
m_operatorController.a("feed").onTrue(spindex.feedNoteToShooter());
173-
m_operatorController.x("sub").onTrue(pivotShooter.setSub());
174-
m_operatorController.y("zero").onTrue(pivotShooter.setPosition(0));
175168
}
176169

177170
private void configureRumble() {
@@ -425,6 +418,6 @@ public Command getAutonomousCommand() {
425418

426419
public void periodic() {
427420
autoChooser.update();
428-
// superstructure.periodic();
421+
superstructure.periodic();
429422
}
430423
}

src/main/java/frc/robot/subsystems/Superstructure.java

Lines changed: 10 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,8 @@ public static enum StructureState {
4040
FEEDING,
4141
TRAP_PREP,
4242
TRAPPING,
43-
POST_TRAP
43+
POST_TRAP,
44+
INTAKE
4445
}
4546

4647
private final Ampevator ampevator;
@@ -125,10 +126,7 @@ public void configStateTransitions() {
125126
.onTrue(setState(StructureState.HOME));
126127
stateTriggers
127128
.get(StructureState.SUB_PREP)
128-
.onTrue(spindex.goToShooter())
129-
.onTrue(
130-
pivotShooter.setPosition(
131-
PivotShooterConstants.kSubWooferPreset * PivotShooterConstants.kPivotMotorGearing))
129+
.onTrue(pivotShooter.setPosition(PivotShooterConstants.kSubWooferPreset))
132130
.onTrue(
133131
shooter.setVelocity(
134132
ShooterConstants.kShooterSpeakerRPS, ShooterConstants.kShooterFollowerSpeakerRPS))
@@ -141,6 +139,13 @@ public void configStateTransitions() {
141139
.onTrue(spindex.feedNoteToShooter())
142140
.and(spindex.debouncedBeamBreak.debounce(1))
143141
.onTrue(setState(StructureState.HOME));
142+
stateTriggers
143+
.get(StructureState.INTAKE)
144+
.onTrue(intake.intakeIn())
145+
.onTrue(spindex.goToShooter())
146+
.onTrue(turret.setPosition(TurretConstants.kIntakePreset))
147+
.and(spindex.debouncedBeamBreak.debounce(0.5))
148+
.onTrue(setState(StructureState.IDLE));
144149
}
145150

146151
// call manually

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

Lines changed: 2 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -75,11 +75,6 @@ public Command off() {
7575
return this.runOnce(pivotShooterIO::off);
7676
}
7777

78-
public Command setSub() {
79-
return setPosition(
80-
PivotShooterConstants.kSubWooferPreset * PivotShooterConstants.kPivotMotorGearing);
81-
}
82-
8378
public Command zero() {
8479
return this.runOnce(pivotShooterIO::zero);
8580
}
@@ -89,9 +84,8 @@ public Command bruh(Vision vision) {
8984
() -> {
9085
pivotShooterIO.setPosition(
9186
aprilTagMap.get(
92-
(vision.getLastCenterLimelightY() - vision.getLastLastCenterLimelightY())
93-
+ vision.getCenterLimelightY())
94-
* PivotShooterConstants.kPivotMotorGearing);
87+
(vision.getLastCenterLimelightY() - vision.getLastLastCenterLimelightY())
88+
+ vision.getCenterLimelightY()));
9589
});
9690
}
9791

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

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -17,14 +17,11 @@
1717
public final class PivotShooterConstants {
1818
// public static final double kSubWooferPreset = (3.5 + 0.3) / 138.33; // idk if
1919
// this works
20-
public static final double kSubWooferPreset = 3.4 / 138.33; // 3.2
21-
public static final double kFeederPreset = 5.9 / 138.33;
20+
public static final double kSubWooferPreset = 3.4; // 3.2
21+
public static final double kFeederPreset = 5.9;
2222

2323
public static final int kPivotMotorID = 51;
2424

25-
/* Physics/geometry */
26-
public static final double kPivotMotorGearing = 138.333; // TODO: get from nate
27-
2825
// max value is 8, min is 0
2926

3027
/* Misc */

src/main/java/frc/robot/subsystems/pivotshooter/PivotShooterIO.java

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,11 +17,9 @@ public static class PivotShooterIOInputs {
1717
public double pivotShooterMotorVoltage = 0.0;
1818
public double pivotShooterMotorVelocity = 0.0;
1919
public double pivotShooterMotorPosition = 0.0;
20-
public double pivotShooterMotorDegrees = 0.0;
2120
public double pivotShooterMotorStatorCurrent = 0.0;
2221
public double pivotShooterMotorSupplyCurrent = 0.0;
2322
public double pivotShooterMotorTemperature = 0.0;
24-
public double pivotShooterMotorReferenceSlope = 0.0;
2523
}
2624

2725
public default void updateInputs(PivotShooterIOInputs inputs) {}

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

Lines changed: 2 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -34,8 +34,6 @@ public class PivotShooterIOTalonFX implements PivotShooterIO {
3434
pivotShooterMotor.getSupplyCurrent();
3535
private final StatusSignal<Double> pivotShooterMotorTemperature =
3636
pivotShooterMotor.getDeviceTemp();
37-
private final StatusSignal<Double> pivotShooterMotorReferenceSlope =
38-
pivotShooterMotor.getClosedLoopReferenceSlope();
3937

4038
public PivotShooterIOTalonFX() {
4139
PhoenixUtil.applyMotorConfigs(
@@ -50,8 +48,7 @@ public PivotShooterIOTalonFX() {
5048
pivotShooterMotorPosition,
5149
pivotShooterMotorStatorCurrent,
5250
pivotShooterMotorSupplyCurrent,
53-
pivotShooterMotorTemperature,
54-
pivotShooterMotorReferenceSlope);
51+
pivotShooterMotorTemperature);
5552
pivotShooterMotor.optimizeBusUtilization();
5653
}
5754

@@ -63,17 +60,13 @@ public void updateInputs(PivotShooterIOInputs inputs) {
6360
pivotShooterMotorPosition,
6461
pivotShooterMotorStatorCurrent,
6562
pivotShooterMotorSupplyCurrent,
66-
pivotShooterMotorTemperature,
67-
pivotShooterMotorReferenceSlope);
63+
pivotShooterMotorTemperature);
6864
inputs.pivotShooterMotorVoltage = pivotShooterMotorVoltage.getValueAsDouble();
6965
inputs.pivotShooterMotorVelocity = pivotShooterMotorVelocity.getValueAsDouble();
7066
inputs.pivotShooterMotorPosition = pivotShooterMotorPosition.getValueAsDouble();
71-
inputs.pivotShooterMotorDegrees =
72-
(inputs.pivotShooterMotorPosition / PivotShooterConstants.kPivotMotorGearing) * 360;
7367
inputs.pivotShooterMotorStatorCurrent = pivotShooterMotorStatorCurrent.getValueAsDouble();
7468
inputs.pivotShooterMotorSupplyCurrent = pivotShooterMotorSupplyCurrent.getValueAsDouble();
7569
inputs.pivotShooterMotorTemperature = pivotShooterMotorTemperature.getValueAsDouble();
76-
inputs.pivotShooterMotorReferenceSlope = pivotShooterMotorReferenceSlope.getValueAsDouble();
7770
}
7871

7972
@Override

src/main/java/frc/robot/subsystems/shooter/ShooterConstants.java

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,8 @@ public final class ShooterConstants {
5757
motorConfigs.withMotorOutput(
5858
motorOutputConfigs.withInverted(InvertedValue.Clockwise_Positive));
5959

60-
public static double kShooterSpeakerRPS = -30;
60+
public static double kShooterSpeakerRPS =
61+
-30; // i got tired of trying to reverse the shooter wheels
6162
public static double kShooterFollowerSpeakerRPS = 60; // really 80
6263

6364
public static double kShooterSubwooferRPS = -60;

0 commit comments

Comments
 (0)