Skip to content

Commit 59b7f45

Browse files
committed
cleaned up hopper
1 parent 84f7c51 commit 59b7f45

File tree

6 files changed

+62
-66
lines changed

6 files changed

+62
-66
lines changed

src/main/java/frc/robot/Subsystems/Hopper/Hopper.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ public static Hopper getInstance() {
3232
@Override
3333
protected void runState() {
3434
io.setTargetSpinVelocity(getState().getSpinVelocity());
35-
io.setTargetKickVelocity(getState().getKickVelocity(), getState().getKickVelocity2());
35+
io.setTargetKickerVelocity(getState().getKickVelocity());
3636
io.updateOutputs(outputs);
3737

3838
Logger.recordOutput(HopperConstants.SUBSYSTEM_NAME + "/SpinVelocityRPS", outputs.spinVelocityRPS);

src/main/java/frc/robot/Subsystems/Hopper/HopperConstants.java

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,6 @@ public class HopperConstants {
77
public static final double OFF_VELOCITY = 0;
88

99
public static final double SPIN_KICK_VELOCITY = -1;
10-
public static final double SPIN_KICK_VELOCITY_2 = -1;
1110

1211
public static final String SUBSYSTEM_NAME = "Hopper";
1312

src/main/java/frc/robot/Subsystems/Hopper/HopperIO.java

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,6 @@ public class HopperIOOutputs {
55

66
double targetSpinVelocity;
77
double targetKickVelocity;
8-
double targetKickVelocity2;
98
double spinVelocityRPS;
109
double kickVelocityRPS;
1110
}
@@ -14,5 +13,5 @@ public class HopperIOOutputs {
1413

1514
public void setTargetSpinVelocity(double velocity);
1615

17-
public void setTargetKickVelocity(double velocity, double velocity2);
16+
public void setTargetKickerVelocity(double velocity);
1817
}

src/main/java/frc/robot/Subsystems/Hopper/HopperIOReal.java

Lines changed: 5 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,9 @@
33
import static edu.wpi.first.units.Units.RotationsPerSecond;
44
import static frc.robot.Subsystems.Hopper.HopperConstants.*;
55

6+
import com.ctre.phoenix6.controls.Follower;
67
import com.ctre.phoenix6.hardware.TalonFX;
8+
import com.ctre.phoenix6.signals.MotorAlignmentValue;
79

810
public class HopperIOReal implements HopperIO {
911

@@ -12,22 +14,20 @@ public class HopperIOReal implements HopperIO {
1214
protected TalonFX kickerMotor2;
1315
double targetSpinVelocity;
1416
double targetKickerVelocity;
15-
double targetKicker2Velocity;
1617

1718
public HopperIOReal() {
18-
//TODO: ADD FOLLOWER MOTORS
1919
spindexerMotor = new TalonFX(SPINDEXER_MOTOR_ID);
2020
kickerMotor = new TalonFX(KICKER_MOTOR_ID);
2121
kickerMotor2 = new TalonFX(KICKER_MOTOR_2_ID);
22+
kickerMotor2.setControl(new Follower(KICKER_MOTOR_ID, MotorAlignmentValue.Opposed));
2223
}
2324

2425
@Override
2526
public void updateOutputs(HopperIOOutputs outputs) {
2627
outputs.spinVelocityRPS = spindexerMotor.getVelocity().getValue().in(RotationsPerSecond);
28+
outputs.kickVelocityRPS = kickerMotor.getVelocity().getValue().in(RotationsPerSecond);
2729
outputs.targetSpinVelocity = targetSpinVelocity;
2830
outputs.targetKickVelocity = targetKickerVelocity;
29-
outputs.kickVelocityRPS = kickerMotor.getVelocity().getValue().in(RotationsPerSecond);
30-
outputs.targetKickVelocity2 = targetKicker2Velocity;
3131
}
3232

3333
@Override
@@ -37,10 +37,8 @@ public void setTargetSpinVelocity(double targetSpinVelocity) {
3737
}
3838

3939
@Override
40-
public void setTargetKickVelocity(double targetKickVelocity, double targetKickVelocity2) {
40+
public void setTargetKickerVelocity(double targetKickVelocity) {
4141
this.targetKickerVelocity = targetKickVelocity;
42-
this.targetKicker2Velocity = targetKickVelocity2;
4342
kickerMotor.set(targetKickVelocity);
44-
kickerMotor2.set(-targetKickVelocity2);
4543
}
4644
}
Lines changed: 52 additions & 51 deletions
Original file line numberDiff line numberDiff line change
@@ -1,51 +1,52 @@
1-
// package frc.robot.Subsystems.Hopper;
2-
3-
// import static edu.wpi.first.units.Units.RotationsPerSecond;
4-
5-
// import com.ctre.phoenix6.sim.TalonFXSimState;
6-
// import edu.wpi.first.math.system.plant.DCMotor;
7-
// import edu.wpi.first.math.system.plant.LinearSystemId;
8-
// import edu.wpi.first.wpilibj.simulation.DCMotorSim;
9-
// import frc.robot.Subsystems.Hopper.HopperConstants.Sim;
10-
11-
// public class HopperIOSim extends HopperIOReal {
12-
13-
// private final TalonFXSimState spindexerSimState;
14-
// private final TalonFXSimState kickerSimState;
15-
// private final DCMotorSim spindexerSim;
16-
// private final DCMotorSim kickerSim;
17-
18-
// double targetSpinVelocity;
19-
// double targetKickVelocity;
20-
21-
// public HopperIOSim() {
22-
// spindexerSimState = new TalonFXSimState(spindexerMotor);
23-
// spindexerSim = new DCMotorSim(LinearSystemId.createDCMotorSystem(DCMotor.getFalcon500(1), Sim.MOTOR_MOI, 1), DCMotor.getFalcon500(1));
24-
25-
// kickerSimState = new TalonFXSimState(kickerMotor);
26-
// kickerSim = new DCMotorSim(LinearSystemId.createDCMotorSystem(DCMotor.getFalcon500(1), Sim.MOTOR_MOI, 1), DCMotor.getFalcon500(1));
27-
// }
28-
29-
// @Override
30-
// public void updateOutputs(HopperIOOutputs outputs) {
31-
// outputs.spinVelocityRPS = spindexerSim.getAngularVelocity().in(RotationsPerSecond);
32-
// outputs.targetSpinVelocity = targetSpinVelocity;
33-
// outputs.targetKickVelocity = targetKickVelocity;
34-
// outputs.kickVelocityRPS = kickerSim.getAngularVelocity().in(RotationsPerSecond);
35-
36-
// spindexerSimState.setRotorVelocity(spindexerSim.getAngularVelocity());
37-
// kickerSimState.setRotorVelocity(kickerSim.getAngularVelocity());
38-
// }
39-
40-
// @Override
41-
// public void setTargetSpinVelocity(double targetSpinVelocity) {
42-
// this.targetSpinVelocity = targetSpinVelocity;
43-
// spindexerMotor.set(targetSpinVelocity);
44-
// }
45-
46-
// @Override
47-
// public void setTargetKickVelocity(double targetKickVelocity) {
48-
// this.targetKickVelocity = targetKickVelocity;
49-
// kickerMotor.set(targetKickVelocity);
50-
// }
51-
// }
1+
package frc.robot.Subsystems.Hopper;
2+
3+
import static edu.wpi.first.units.Units.RotationsPerSecond;
4+
5+
import com.ctre.phoenix6.sim.TalonFXSimState;
6+
import edu.wpi.first.math.system.plant.DCMotor;
7+
import edu.wpi.first.math.system.plant.LinearSystemId;
8+
import edu.wpi.first.wpilibj.simulation.DCMotorSim;
9+
import frc.robot.Subsystems.Hopper.HopperConstants.Sim;
10+
11+
public class HopperIOSim extends HopperIOReal {
12+
13+
private final TalonFXSimState spindexerSimState;
14+
private final TalonFXSimState kickerSimState;
15+
private final DCMotorSim spindexerSim;
16+
private final DCMotorSim kickerSim;
17+
18+
double targetSpinVelocity;
19+
double targetKickerVelocity;
20+
double targetKickerVelocity2;
21+
22+
public HopperIOSim() {
23+
spindexerSimState = new TalonFXSimState(spindexerMotor);
24+
spindexerSim = new DCMotorSim(LinearSystemId.createDCMotorSystem(DCMotor.getFalcon500(1), Sim.MOTOR_MOI, 1), DCMotor.getFalcon500(1));
25+
26+
kickerSimState = new TalonFXSimState(kickerMotor);
27+
kickerSim = new DCMotorSim(LinearSystemId.createDCMotorSystem(DCMotor.getFalcon500(1), Sim.MOTOR_MOI, 1), DCMotor.getFalcon500(1));
28+
}
29+
30+
@Override
31+
public void updateOutputs(HopperIOOutputs outputs) {
32+
outputs.spinVelocityRPS = spindexerSim.getAngularVelocity().in(RotationsPerSecond);
33+
outputs.kickVelocityRPS = kickerSim.getAngularVelocity().in(RotationsPerSecond);
34+
outputs.targetSpinVelocity = targetSpinVelocity;
35+
outputs.targetKickVelocity = targetKickerVelocity;
36+
37+
spindexerSimState.setRotorVelocity(spindexerSim.getAngularVelocity());
38+
kickerSimState.setRotorVelocity(kickerSim.getAngularVelocity());
39+
}
40+
41+
@Override
42+
public void setTargetSpinVelocity(double targetSpinVelocity) {
43+
this.targetSpinVelocity = targetSpinVelocity;
44+
spindexerMotor.set(targetSpinVelocity);
45+
}
46+
47+
@Override
48+
public void setTargetKickerVelocity(double velocity) {
49+
this.targetKickerVelocity = velocity;
50+
kickerMotor.set(targetKickerVelocity);
51+
}
52+
}

src/main/java/frc/robot/Subsystems/Hopper/HopperStates.java

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -3,19 +3,18 @@
33
import org.team7525.subsystem.SubsystemStates;
44

55
public enum HopperStates implements SubsystemStates {
6-
IDLE("Idle", HopperConstants.OFF_VELOCITY, HopperConstants.OFF_VELOCITY, HopperConstants.OFF_VELOCITY),
7-
SPINDEXING("Spindexing", HopperConstants.SPIN_KICK_VELOCITY, HopperConstants.SPIN_VELOCITY, HopperConstants.SPIN_KICK_VELOCITY_2);
6+
IDLE("Idle", HopperConstants.OFF_VELOCITY, HopperConstants.OFF_VELOCITY),
7+
SPINDEXING("Spindexing", HopperConstants.SPIN_KICK_VELOCITY, HopperConstants.SPIN_VELOCITY);
88

99
private String stateString;
1010
private double spinVelocity;
1111
private double kickVelocity;
1212
private double kickVelocity2;
1313

14-
HopperStates(String stateString, double kickVelocity, double spinVelocity, double kickVelocity2) {
14+
HopperStates(String stateString, double kickVelocity, double spinVelocity) {
1515
this.stateString = stateString;
1616
this.spinVelocity = spinVelocity;
1717
this.kickVelocity = kickVelocity;
18-
this.kickVelocity2 = kickVelocity2;
1918
}
2019

2120
@Override

0 commit comments

Comments
 (0)