Skip to content

Commit c840b04

Browse files
committed
libs update + basic tuning
1 parent ca446bb commit c840b04

File tree

12 files changed

+143
-105
lines changed

12 files changed

+143
-105
lines changed

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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@ private Hopper() {
1717
outputs = new HopperIOOutputs();
1818
this.io = switch (ROBOT_MODE) {
1919
case REAL -> new HopperIOReal();
20-
case SIM -> new HopperIOSim();
20+
case SIM -> new HopperIOReal();
2121
case TESTING -> new HopperIOReal();
2222
};
2323
}
@@ -32,7 +32,7 @@ public static Hopper getInstance() {
3232
@Override
3333
protected void runState() {
3434
io.setTargetSpinVelocity(getState().getSpinVelocity());
35-
io.setTargetKickVelocity(getState().getKickVelocity());
35+
io.setTargetKickVelocity(getState().getKickVelocity(), getState().getKickVelocity2());
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: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,15 +3,17 @@
33
public class HopperConstants {
44

55
//not real values atm
6-
public static final double SPIN_VELOCITY = -1;
6+
public static final double SPIN_VELOCITY = -0.15;
77
public static final double OFF_VELOCITY = 0;
88

9-
public static final double SPIN_KICK_VELOCITY = -0.7;
9+
public static final double SPIN_KICK_VELOCITY = -1;
10+
public static final double SPIN_KICK_VELOCITY_2 = -1;
1011

1112
public static final String SUBSYSTEM_NAME = "Hopper";
1213

1314
public static final int SPINDEXER_MOTOR_ID = 33;
1415
public static final int KICKER_MOTOR_ID = 34;
16+
public static final int KICKER_MOTOR_2_ID = 50;
1517

1618
public static class Sim {
1719

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

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,13 +5,15 @@ public class HopperIOOutputs {
55

66
double targetSpinVelocity;
77
double targetKickVelocity;
8+
double targetKickVelocity2;
89
double spinVelocityRPS;
910
double kickVelocityRPS;
11+
1012
}
1113

1214
public void updateOutputs(HopperIOOutputs outputs);
1315

1416
public void setTargetSpinVelocity(double velocity);
1517

16-
public void setTargetKickVelocity(double velocity);
18+
public void setTargetKickVelocity(double velocity, double velocity2);
1719
}

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

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,12 +9,15 @@ public class HopperIOReal implements HopperIO {
99

1010
protected TalonFX spindexerMotor;
1111
protected TalonFX kickerMotor;
12+
protected TalonFX kickerMotor2;
1213
double targetSpinVelocity;
1314
double targetKickerVelocity;
15+
double targeKicker2Velociy;
1416

1517
public HopperIOReal() {
1618
spindexerMotor = new TalonFX(SPINDEXER_MOTOR_ID);
1719
kickerMotor = new TalonFX(KICKER_MOTOR_ID);
20+
kickerMotor2 = new TalonFX(KICKER_MOTOR_2_ID);
1821
}
1922

2023
@Override
@@ -23,6 +26,7 @@ public void updateOutputs(HopperIOOutputs outputs) {
2326
outputs.targetSpinVelocity = targetSpinVelocity;
2427
outputs.targetKickVelocity = targetKickerVelocity;
2528
outputs.kickVelocityRPS = kickerMotor.getVelocity().getValue().in(RotationsPerSecond);
29+
outputs.targetKickVelocity2 = targeKicker2Velociy;
2630
}
2731

2832
@Override
@@ -32,8 +36,12 @@ public void setTargetSpinVelocity(double targetSpinVelocity) {
3236
}
3337

3438
@Override
35-
public void setTargetKickVelocity(double targetKickVelocity) {
39+
public void setTargetKickVelocity(double targetKickVelocity, double targetKickVelocity2) {
3640
this.targetKickerVelocity = targetKickVelocity;
41+
this.targeKicker2Velociy = targetKickVelocity2;
3742
kickerMotor.set(targetKickVelocity);
43+
kickerMotor2.set(targetKickVelocity2);
3844
}
45+
46+
3947
}
Lines changed: 51 additions & 51 deletions
Original file line numberDiff line numberDiff line change
@@ -1,51 +1,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 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 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+
// }

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

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

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

99
private String stateString;
1010
private double spinVelocity;
1111
private double kickVelocity;
12+
private double kickVelocity2;
1213

13-
HopperStates(String stateString, double spinVelocity, double kickVelocity) {
14+
15+
HopperStates(String stateString, double kickVelocity, double spinVelocity, double kickVelocity2) {
1416
this.stateString = stateString;
1517
this.spinVelocity = spinVelocity;
1618
this.kickVelocity = kickVelocity;
19+
this.kickVelocity2 = kickVelocity2;
1720
}
1821

1922
@Override
@@ -28,4 +31,9 @@ public double getSpinVelocity() {
2831
public double getKickVelocity() {
2932
return kickVelocity;
3033
}
34+
public double getKickVelocity2() {
35+
36+
return kickVelocity2;
37+
}
38+
3139
}

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

Lines changed: 15 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -21,9 +21,9 @@ public class Manager extends Subsystem<ManagerStates> {
2121
private Drive drive;
2222
private Shooter shooter;
2323
private Hopper hopper;
24-
private Intake intake;
25-
private Climber climber;
26-
private Vision vision;
24+
//private Intake intake;
25+
//private Climber climber;
26+
//private Vision vision;
2727

2828
public static Manager getInstance() {
2929
if (instance == null) {
@@ -38,9 +38,9 @@ private Manager() {
3838
drive = Drive.getInstance();
3939
shooter = Shooter.getInstance();
4040
hopper = Hopper.getInstance();
41-
intake = Intake.getInstance();
42-
climber = Climber.getInstance();
43-
vision = Vision.getInstance();
41+
//intake = Intake.getInstance();
42+
//climber = Climber.getInstance();
43+
//vision = Vision.getInstance();
4444

4545
// IDLE <---> EXTENDED_IDLE
4646
addTrigger(ManagerStates.IDLE, ManagerStates.EXTENDED_IDLE, DRIVER_CONTROLLER::getRightBumperButtonPressed);
@@ -79,6 +79,8 @@ private Manager() {
7979
// EXTENDING_CLIMBER <---> RETRACTING_CLIMBER
8080
addTrigger(ManagerStates.EXTENDING_CLIMBER, ManagerStates.RETRACTING_CLIMBER, OPERATOR_CONTROLLER::getLeftBumperButtonPressed);
8181
addTrigger(ManagerStates.RETRACTING_CLIMBER, ManagerStates.EXTENDING_CLIMBER, OPERATOR_CONTROLLER::getLeftBumperButtonPressed);
82+
83+
addTrigger(ManagerStates.IDLE, ManagerStates.SHOOTING_FIXED, DRIVER_CONTROLLER::getAButtonPressed);
8284
}
8385

8486
@Override
@@ -94,22 +96,22 @@ public void runState() {
9496
}
9597

9698
Logger.recordOutput(SUBSYSTEM_NAME + "/STATE", getState().getStateString());
97-
Logger.recordOutput(SUBSYSTEM_NAME + "/InAllianceShootingPosition", drive.isAtAllianceShootingPosition());
99+
//Logger.recordOutput(SUBSYSTEM_NAME + "/InAllianceShootingPosition", drive.isAtAllianceShootingPosition());
98100
Logger.recordOutput(SUBSYSTEM_NAME + "/STATE TIME", getStateTime());
99101
Logger.recordOutput(SUBSYSTEM_NAME + "/HUB ACTIVE", isHubActive());
100102

101103
// Set subsystem states
102104
shooter.setState(getState().getShooterState());
103105
hopper.setState(getState().getHopperState());
104-
intake.setState(getState().getIntakeState());
105-
climber.setState(getState().getClimberState());
106+
//intake.setState(getState().getIntakeState());
107+
//climber.setState(getState().getClimberState());
106108

107109
Tracer.traceFunc("ShooterPeriodic", shooter::periodic); // SHould these be used with Tracer? idk what that does fr
108110
Tracer.traceFunc("HopperPeriodic", hopper::periodic);
109-
Tracer.traceFunc("IntakePeriodic", intake::periodic);
110-
Tracer.traceFunc("ClimberPeriodic", climber::periodic);
111-
Tracer.traceFunc("DrivePeriodic", drive::periodic);
112-
Tracer.traceFunc("VisionPeriodic", vision::periodic);
111+
//Tracer.traceFunc("IntakePeriodic", intake::periodic);
112+
//Tracer.traceFunc("ClimberPeriodic", climber::periodic);
113+
//Tracer.traceFunc("DrivePeriodic", drive::periodic);
114+
//Tracer.traceFunc("VisionPeriodic", vision::periodic);
113115
// Emergency stop to IDLE
114116
if (DRIVER_CONTROLLER.getStartButton() || OPERATOR_CONTROLLER.getStartButton()) {
115117
setState(ManagerStates.IDLE);

src/main/java/frc/robot/Subsystems/Shooter/ShooterConstants.java

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -18,11 +18,11 @@ public final class ShooterConstants {
1818

1919
public static final String SUBSYSTEM_NAME = "Shooter";
2020
// Preset positions
21-
public static final double HOOD_MIN_ANGLE_RADS = 0.0; // TODO: get real value
22-
public static final double HOOD_MAX_ANGLE_RADS = Math.toRadians(60); // TODO: get real value
21+
public static final Angle HOOD_MIN_ANGLE = Degrees.of(4.8025772); // TODO: get real value
22+
public static final Angle HOOD_MAX_ANGLE = Degrees.of(54.6051544); // TODO: get real value
2323

24-
public static final Angle FIXED_SHOT_ANGLE = Degrees.of(45); //TODO: get good value
25-
public static final AngularVelocity FIXED_SHOT_SPEED = RotationsPerSecond.of(150); //TODO: get good value
24+
public static final Angle FIXED_SHOT_ANGLE = Degrees.of(35); //TODO: get good value
25+
public static final AngularVelocity FIXED_SHOT_SPEED = RotationsPerSecond.of(-10); //TODO: get good value
2626

2727
public static final Angle STANDBY_ANGLE = Degrees.of(45); //TODO: get good value
2828
public static final AngularVelocity STANDBY_SPEED = RotationsPerSecond.of(500); //TODO: get good value
@@ -39,7 +39,7 @@ public final class ShooterConstants {
3939
public static final double FLYWHEEL_MOI = 0.00117056; // Roughly accurate for flywheel
4040
public static final double FLYWHEEL_GEARING = 1.0; // Also roughly accurate
4141
public static final double HOOD_MOI = 0.0001;
42-
public static final double HOOD_GEARING = 1.0;
42+
public static final double HOOD_GEARING = 75; //100/3 previously,
4343
public static final double HOOD_ARM_LENGTH_METERS = 0.2;
4444

4545
// State defaults
@@ -51,19 +51,19 @@ public final class ShooterConstants {
5151

5252
public static final Supplier<PIDController> HOOD_PID = () ->
5353
switch (GlobalConstants.ROBOT_MODE) {
54-
case REAL -> new PIDController(1, 0, 0);
54+
case REAL -> new PIDController(0.04, 0.0002, 0.0); //.0384 good alr
5555
case SIM -> new PIDController(0.04, 0, 0.001); // Tuned in sim
56-
case TESTING -> new PIDController(1, 0, 0);
56+
case TESTING -> new PIDController(0, 0, 0);
5757
}; //TODO: tune
5858
public static final Supplier<PIDController> WHEEL_PID = () ->
5959
switch (GlobalConstants.ROBOT_MODE) {
60-
case REAL -> new PIDController(0.1, 0, 0);
60+
case REAL -> new PIDController(0, 0, 0);
6161
case SIM -> new PIDController(0.0077, 0, 0.00013);
6262
case TESTING -> new PIDController(0.1, 0, 0);
6363
}; //TODO: tune
6464
public static final Supplier<SimpleMotorFeedforward> WHEEL_FEEDFORWARD = () ->
6565
switch (GlobalConstants.ROBOT_MODE) {
66-
case REAL -> new SimpleMotorFeedforward(0.1, 0.01, 0.001);
66+
case REAL -> new SimpleMotorFeedforward(0.0, 0.00, 0.000);
6767
case SIM -> new SimpleMotorFeedforward(0.11, 0.1, 0.0);
6868
case TESTING -> new SimpleMotorFeedforward(0.1, 0.01, 0.001);
6969
}; //TODO: tune

0 commit comments

Comments
 (0)