Skip to content

Commit b79b4c0

Browse files
Tortuga-AMgithub-actionsCopilotGreenTomato5
authored
Shooter and Hood (#4)
* Buns placeholder * AdjustableHood * Shooter * HoodedShooterSupersystem * Global Constants Comment * Fixes + Magic Numbers * Apply Prettier format * Magic ahh numbers * Apply Prettier format * @PotmanNob your CI stuff is buns fr * Update src/main/java/frc/robot/Subsystems/AdjustableHood/AdjustableHood.java oops :( Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> * More constants * Copilot Fix 1 Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> * Fixing buns CI stuff * Fixing requested changes * Apply Prettier format --------- Co-authored-by: github-actions <github-actions@github.com> Co-authored-by: Copilot <175728472+Copilot@users.noreply.github.com> Co-authored-by: Otto Watson-Brown <ottowatsonbrown@icloud.com>
1 parent 92ad5a9 commit b79b4c0

19 files changed

+668
-8
lines changed

.github/scripts/constants.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ def check_for_magic_numbers(file_path):
6161

6262
def is_file_excused(file_path, project_root):
6363
filename = os.path.basename(file_path)
64-
if filename in excused_files:
64+
if filename in excused_files or 'constants' in filename.lower():
6565
return True
6666

6767
relative_path = os.path.relpath(file_path, project_root)

src/main/java/frc/robot/GlobalConstants.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,7 @@ public enum RobotMode {
1010
SIM,
1111
} // No point in having replay tbh
1212

13-
public static final RobotMode ROBOT_MODE = RobotBase.isReal() ? RobotMode.REAL : RobotMode.SIM; // Change this to TESTING or SIM for testing purposes
13+
public static final RobotMode ROBOT_MODE = RobotBase.isReal() ? RobotMode.REAL : RobotMode.SIM; // Change this to TESTING for testing purposes
1414

1515
public static final double SIMULATION_PERIOD = 0.02;
1616
}
Lines changed: 57 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,57 @@
1+
package frc.robot.Subsystems.AdjustableHood;
2+
3+
import static frc.robot.GlobalConstants.*;
4+
import static frc.robot.Subsystems.AdjustableHood.AdjustableHoodConstants.SUBSYSTEM_NAME;
5+
6+
import edu.wpi.first.units.measure.Angle;
7+
import org.littletonrobotics.junction.Logger;
8+
import org.team7525.subsystem.Subsystem;
9+
10+
public class AdjustableHood extends Subsystem<AdjustableHoodStates> {
11+
12+
private AdjustableHoodIO io;
13+
private AdjustableHoodIOInputsAutoLogged inputs;
14+
private Angle dynamicSetpoint;
15+
private static AdjustableHood instance;
16+
17+
public static AdjustableHood getInstance() {
18+
if (instance == null) {
19+
AdjustableHoodIO AdjustableHoodio =
20+
switch (ROBOT_MODE) {
21+
case SIM -> new AdjustableHoodIOSim();
22+
case REAL -> new AdjustableHoodIOReal();
23+
case TESTING -> new AdjustableHoodIOReal();
24+
};
25+
instance = new AdjustableHood(AdjustableHoodio);
26+
}
27+
28+
return instance;
29+
}
30+
31+
private AdjustableHood(AdjustableHoodIO io) {
32+
super(SUBSYSTEM_NAME, AdjustableHoodStates.IDLE);
33+
this.io = io;
34+
inputs = new AdjustableHoodIOInputsAutoLogged();
35+
}
36+
37+
@Override
38+
public void runState() {
39+
if (getState() == AdjustableHoodStates.DYNAMIC) {
40+
io.setHoodSetpoint(dynamicSetpoint);
41+
} else {
42+
io.setHoodSetpoint(getState().getSetpoint());
43+
}
44+
45+
io.updateInputs(inputs);
46+
Logger.processInputs(SUBSYSTEM_NAME, inputs);
47+
Logger.recordOutput(SUBSYSTEM_NAME + "/State", getState().getStateString());
48+
}
49+
50+
public void setDynamicHoodSetpoint(Angle setpoint) {
51+
dynamicSetpoint = setpoint;
52+
}
53+
54+
public boolean atSetpoint() {
55+
return io.atHoodSetpoint();
56+
}
57+
}
Lines changed: 53 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,53 @@
1+
package frc.robot.Subsystems.AdjustableHood;
2+
3+
import static edu.wpi.first.units.Units.Degrees;
4+
import static edu.wpi.first.units.Units.Inches;
5+
import static edu.wpi.first.units.Units.KilogramSquareMeters;
6+
import static frc.robot.GlobalConstants.ROBOT_MODE;
7+
8+
import edu.wpi.first.math.controller.ProfiledPIDController;
9+
import edu.wpi.first.math.trajectory.TrapezoidProfile;
10+
import edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints;
11+
import edu.wpi.first.units.measure.Angle;
12+
import edu.wpi.first.units.measure.Distance;
13+
import edu.wpi.first.units.measure.MomentOfInertia;
14+
import java.util.function.Supplier;
15+
16+
public class AdjustableHoodConstants {
17+
18+
public static final String SUBSYSTEM_NAME = "Adjustable Hood";
19+
20+
public static final Angle IDLE_ANGLE = Degrees.of(0);
21+
public static final Angle FIXED_ANGLE = Degrees.of(45);
22+
23+
public static final Angle MAX_ANGLE = Degrees.of(60);
24+
public static final Angle MIN_ANGLE = Degrees.of(0);
25+
26+
public static final Constraints constraints = new TrapezoidProfile.Constraints(
27+
Math.toRadians(180), // Max angular velocity in radians per second (random)
28+
Math.toRadians(90) // Max angular acceleration in radians per second squared (random)
29+
);
30+
31+
public static final Supplier<ProfiledPIDController> PIVOT_PID = () ->
32+
switch (ROBOT_MODE) {
33+
case SIM -> new ProfiledPIDController(0.1, 0, 0.01, constraints);
34+
default -> new ProfiledPIDController(0.1, 0, 0.01, constraints);
35+
};
36+
37+
public static final class Real {
38+
39+
public static final Angle PIVOT_TOLERANCE = Degrees.of(0.5); // Random tolerance of 0.5 degrees
40+
public static final int PIVOT_CAN_ID = 1; // Random value
41+
public static final double GEAR_RATIO = 25; // Random ahh gear ratio of 25:1
42+
}
43+
44+
public static final class Sim {
45+
46+
public static final Angle PIVOT_TOLERANCE = Degrees.of(0.5); // Random tolerance of 0.5 degrees
47+
public static final double GEAR_RATIO = 25; // Random ahh gear ratio of 25:1
48+
public static final MomentOfInertia PIVOT_MOI = KilogramSquareMeters.of(1); // Random moment of inertia
49+
public static final Distance PIVOT_LENGTH = Inches.of(8); // Random length of 8 inches
50+
public static final int NUM_PIVOT_MOTORS = 1; // Number of motors used for the pivot
51+
public static final Angle PIVOT_STARTING_ANGLE = Degrees.of(0); // Starting angle of the pivot motor
52+
}
53+
}
Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
package frc.robot.Subsystems.AdjustableHood;
2+
3+
import edu.wpi.first.units.measure.Angle;
4+
import org.littletonrobotics.junction.AutoLog;
5+
6+
public interface AdjustableHoodIO {
7+
@AutoLog
8+
public static class AdjustableHoodIOInputs {
9+
10+
public Angle hoodSetpoint;
11+
public double hoodPosition;
12+
}
13+
14+
public abstract void updateInputs(AdjustableHoodIOInputs inputs);
15+
16+
public abstract void setHoodSetpoint(Angle setpoint);
17+
18+
public abstract boolean atHoodSetpoint();
19+
}
Lines changed: 61 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,61 @@
1+
package frc.robot.Subsystems.AdjustableHood;
2+
3+
import static edu.wpi.first.units.Units.Rotations;
4+
import static frc.robot.GlobalConstants.ROBOT_MODE;
5+
import static frc.robot.Subsystems.AdjustableHood.AdjustableHoodConstants.PIVOT_PID;
6+
import static frc.robot.Subsystems.AdjustableHood.AdjustableHoodConstants.Real.*;
7+
8+
import com.ctre.phoenix6.hardware.TalonFX;
9+
import edu.wpi.first.math.controller.ProfiledPIDController;
10+
import edu.wpi.first.math.util.Units;
11+
import edu.wpi.first.units.measure.Angle;
12+
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
13+
import frc.robot.GlobalConstants.RobotMode;
14+
15+
public class AdjustableHoodIOReal implements AdjustableHoodIO {
16+
17+
private TalonFX pivotMotor;
18+
private Angle hoodSetpoint;
19+
private ProfiledPIDController pivotController;
20+
21+
public AdjustableHoodIOReal() {
22+
pivotMotor = new TalonFX(PIVOT_CAN_ID);
23+
pivotMotor.setPosition(0); // Zero the motor position
24+
pivotController = PIVOT_PID.get();
25+
pivotController.setTolerance(PIVOT_TOLERANCE.in(Rotations));
26+
}
27+
28+
@Override
29+
public void updateInputs(AdjustableHoodIOInputs inputs) {
30+
inputs.hoodSetpoint = hoodSetpoint;
31+
inputs.hoodPosition = Units.rotationsToDegrees(
32+
pivotMotor.getPosition().getValueAsDouble() / GEAR_RATIO
33+
);
34+
35+
if (ROBOT_MODE == RobotMode.TESTING) {
36+
SmartDashboard.putData("Hood PID Controller", pivotController);
37+
}
38+
}
39+
40+
@Override
41+
public void setHoodSetpoint(Angle hoodSetpoint) {
42+
this.hoodSetpoint = hoodSetpoint;
43+
pivotMotor.set(
44+
pivotController.calculate(
45+
pivotMotor.getPosition().getValueAsDouble() / GEAR_RATIO,
46+
hoodSetpoint.in(Rotations)
47+
)
48+
);
49+
}
50+
51+
@Override
52+
public boolean atHoodSetpoint() {
53+
return (
54+
Math.abs(
55+
(pivotMotor.getPosition().getValueAsDouble() / GEAR_RATIO) -
56+
hoodSetpoint.in(Rotations)
57+
) <
58+
PIVOT_TOLERANCE.in(Rotations)
59+
);
60+
}
61+
}
Lines changed: 73 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,73 @@
1+
package frc.robot.Subsystems.AdjustableHood;
2+
3+
import static edu.wpi.first.units.Units.Degrees;
4+
import static edu.wpi.first.units.Units.KilogramSquareMeters;
5+
import static edu.wpi.first.units.Units.Meters;
6+
import static edu.wpi.first.units.Units.Radians;
7+
import static frc.robot.GlobalConstants.SIMULATION_PERIOD;
8+
import static frc.robot.Subsystems.AdjustableHood.AdjustableHoodConstants.*;
9+
10+
import com.ctre.phoenix6.hardware.TalonFX;
11+
import com.ctre.phoenix6.sim.TalonFXSimState;
12+
import edu.wpi.first.math.controller.ProfiledPIDController;
13+
import edu.wpi.first.math.system.plant.DCMotor;
14+
import edu.wpi.first.math.util.Units;
15+
import edu.wpi.first.units.measure.Angle;
16+
import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim;
17+
18+
public class AdjustableHoodIOSim implements AdjustableHoodIO {
19+
20+
private TalonFX pivotMotor;
21+
private TalonFXSimState pivotMotorTalonSim;
22+
private SingleJointedArmSim pivotSim;
23+
private ProfiledPIDController pivotController;
24+
private Angle pivotSetpoint;
25+
26+
public AdjustableHoodIOSim() {
27+
pivotMotor = new TalonFX(Real.PIVOT_CAN_ID);
28+
pivotMotorTalonSim = pivotMotor.getSimState();
29+
pivotSim = new SingleJointedArmSim(
30+
DCMotor.getKrakenX60(Sim.NUM_PIVOT_MOTORS),
31+
Sim.GEAR_RATIO,
32+
Sim.PIVOT_MOI.in(KilogramSquareMeters),
33+
Sim.PIVOT_LENGTH.in(Meters),
34+
MIN_ANGLE.in(Radians),
35+
MAX_ANGLE.in(Radians),
36+
false,
37+
Sim.PIVOT_STARTING_ANGLE.in(Radians)
38+
);
39+
40+
pivotController = PIVOT_PID.get();
41+
pivotController.setTolerance(Sim.PIVOT_TOLERANCE.in(Radians));
42+
pivotSetpoint = Sim.PIVOT_STARTING_ANGLE;
43+
}
44+
45+
@Override
46+
public void updateInputs(AdjustableHoodIOInputs inputs) {
47+
pivotSim.update(SIMULATION_PERIOD);
48+
49+
inputs.hoodSetpoint = pivotSetpoint;
50+
inputs.hoodPosition = Units.radiansToDegrees(pivotSim.getAngleRads());
51+
52+
pivotMotorTalonSim.setRawRotorPosition(Units.radiansToRotations(pivotSim.getAngleRads()));
53+
pivotMotorTalonSim.setRotorVelocity(
54+
Units.radiansToRotations(pivotSim.getVelocityRadPerSec())
55+
);
56+
}
57+
58+
@Override
59+
public void setHoodSetpoint(Angle setpoint) {
60+
pivotSetpoint = setpoint;
61+
pivotSim.setInputVoltage(
62+
pivotController.calculate(
63+
Units.radiansToDegrees(pivotSim.getAngleRads()),
64+
pivotSetpoint.in(Degrees)
65+
)
66+
);
67+
}
68+
69+
@Override
70+
public boolean atHoodSetpoint() {
71+
return pivotController.atSetpoint();
72+
}
73+
}
Lines changed: 31 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,31 @@
1+
package frc.robot.Subsystems.AdjustableHood;
2+
3+
import static frc.robot.Subsystems.AdjustableHood.AdjustableHoodConstants.*;
4+
5+
import edu.wpi.first.units.measure.Angle;
6+
import frc.robot.Subsystems.HoodedShooterSupersystem.HoodedShooterSupersystem;
7+
import java.util.function.Supplier;
8+
import org.team7525.subsystem.SubsystemStates;
9+
10+
public enum AdjustableHoodStates implements SubsystemStates {
11+
IDLE("IDLE", () -> IDLE_ANGLE),
12+
FIXED("FIXED", () -> FIXED_ANGLE),
13+
DYNAMIC("DYNAMIC", () -> HoodedShooterSupersystem.getInstance().calculateHoodSetpoint());
14+
15+
private final String stateName;
16+
private final Supplier<Angle> setpointSupplier;
17+
18+
AdjustableHoodStates(String stateName, Supplier<Angle> setpointSupplier) {
19+
this.stateName = stateName;
20+
this.setpointSupplier = setpointSupplier;
21+
}
22+
23+
@Override
24+
public String getStateString() {
25+
return stateName;
26+
}
27+
28+
public Angle getSetpoint() {
29+
return setpointSupplier.get();
30+
}
31+
}

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

Lines changed: 0 additions & 5 deletions
This file was deleted.
Lines changed: 62 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,62 @@
1+
package frc.robot.Subsystems.HoodedShooterSupersystem;
2+
3+
import static edu.wpi.first.units.Units.Degrees;
4+
import static edu.wpi.first.units.Units.RotationsPerSecond;
5+
import static frc.robot.Subsystems.HoodedShooterSupersystem.HoodedShooterSupersystemConstants.*;
6+
7+
import edu.wpi.first.units.measure.Angle;
8+
import edu.wpi.first.units.measure.AngularVelocity;
9+
import frc.robot.Subsystems.AdjustableHood.AdjustableHood;
10+
import frc.robot.Subsystems.Shooter.Shooter;
11+
import org.littletonrobotics.junction.Logger;
12+
import org.team7525.subsystem.Subsystem;
13+
14+
public class HoodedShooterSupersystem extends Subsystem<HoodedShooterSupersystemStates> {
15+
16+
private static HoodedShooterSupersystem instance;
17+
private AdjustableHood hood;
18+
private Shooter shooter;
19+
20+
public static HoodedShooterSupersystem getInstance() {
21+
if (instance == null) {
22+
instance = new HoodedShooterSupersystem();
23+
}
24+
return instance;
25+
}
26+
27+
private HoodedShooterSupersystem() {
28+
super(SUBSYSTEM_NAME, HoodedShooterSupersystemStates.IDLE);
29+
hood = AdjustableHood.getInstance();
30+
shooter = Shooter.getInstance();
31+
}
32+
33+
@Override
34+
public void runState() {
35+
hood.setState(getState().getAdjustableHoodState());
36+
shooter.setState(getState().getShooterState());
37+
38+
hood.periodic();
39+
shooter.periodic();
40+
41+
Logger.recordOutput(SUBSYSTEM_NAME + "/State", getState().getStateString());
42+
}
43+
44+
/*
45+
* Checks if the hood and shooter are both at their setpoints.
46+
* The manager subsystem should use this method to determine when to switch from warming up to shooting.
47+
* Those states should be identical but one tells the indexer to pass the ball to the shooter.
48+
*/
49+
public boolean readyToShoot() {
50+
return hood.atSetpoint() && shooter.atSetpoint();
51+
}
52+
53+
public Angle calculateHoodSetpoint() {
54+
// Placeholder for actual hood setpoint calculation logic
55+
return Degrees.of(FAKE_VALUE); // Replace with actual calculation
56+
}
57+
58+
public AngularVelocity calculateShooterSetpoint() {
59+
// Placeholder for actual shooter setpoint calculation logic
60+
return RotationsPerSecond.of(FAKE_VALUE_2); // Replace with actual calculation
61+
}
62+
}

0 commit comments

Comments
 (0)