Skip to content
This repository has been archived by the owner on May 19, 2024. It is now read-only.

Commit

Permalink
refactor(shooter): WIP.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Apr 26, 2024
1 parent 0dc9253 commit 7abd089
Show file tree
Hide file tree
Showing 8 changed files with 176 additions and 183 deletions.
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/intake/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
import frc.lib.controller.VelocityControllerIO;
import frc.lib.controller.VelocityControllerIO.VelocityControllerIOValues;

/** Subsystem class for the intake subsystem. */
/** Intake subsystem. */
public class Intake extends Subsystem {

/** Intake singleton. */
Expand Down Expand Up @@ -83,8 +83,8 @@ private Intake() {

backRollerValues = new VelocityControllerIOValues();

setpoint = IntakeState.IDLE;
goal = IntakeState.IDLE;
setpoint = IntakeState.IDLING;
goal = IntakeState.IDLING;
}

/**
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/intake/IntakeState.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@
public record IntakeState(
double frontRollerVelocityRotationsPerSecond, double backRollerVelocityRotationsPerSecond) {

/** Idle state. */
public static final IntakeState IDLE = new IntakeState(0, 0);
/** Idling state. */
public static final IntakeState IDLING = new IntakeState(0, 0);

/** Intaking state. */
public static final IntakeState INTAKING = new IntakeState(34.0, 34.0);
Expand Down
154 changes: 119 additions & 35 deletions src/main/java/frc/robot/shooter/Shooter.java
Original file line number Diff line number Diff line change
@@ -1,51 +1,112 @@
package frc.robot.shooter;

import edu.wpi.first.math.filter.SlewRateLimiter;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.lib.Subsystem;
import frc.lib.config.FeedbackControllerConfig;
import frc.lib.config.FeedforwardControllerConfig;
import frc.lib.config.MechanismConfig;
import frc.lib.config.MotionProfileConfig;
import frc.lib.config.MotorConfig;
import frc.lib.controller.VelocityControllerIO;
import frc.lib.controller.VelocityControllerIO.VelocityControllerIOValues;
import frc.robot.shooter.ShooterConstants.FlywheelConstants;
import frc.robot.shooter.ShooterConstants.SerializerConstants;

/** Subsystem class for the shooter subsystem. */
/** Shooter subsystem. */
public class Shooter extends Subsystem {

/** Instance variable for the shooter subsystem singleton. */
/** Shooter singleton. */
private static Shooter instance = null;

/** Serializer. */
private final MechanismConfig flywheelConfig =
new MechanismConfig()
.withMotorConfig(
new MotorConfig()
.withCCWPositive(false)
.withNeutralBrake(true)
.withMotorToMechanismRatio(28.0 / 16.0))
.withMotionProfileConfig(
new MotionProfileConfig()
.withMaximumVelocity(60) // rotations per second
.withMaximumAcceleration(200) // rotations per second per second
)
.withFeedforwardConfig(
new FeedforwardControllerConfig()
.withStaticFeedforward(0.14) // volts
.withVelocityFeedforward(0.2) // volts per rotation per second
)
.withFeedbackConfig(
new FeedbackControllerConfig()
.withProportionalGain(0.14) // volts per rotation per second
);

/** Flywheel controller. */
private final VelocityControllerIO flywheel;

/** Flywheel controller values. */
private final VelocityControllerIOValues flywheelValues;

/** Flywheel controller acceleration limiter. */
private final SlewRateLimiter flywheelAccelerationLimiter;

/** Serializer config. */
private final MechanismConfig serializerConfig =
new MechanismConfig()
.withMotorConfig(
new MotorConfig()
.withCCWPositive(true)
.withNeutralBrake(false)
.withMotorToMechanismRatio(36.0 / 16.0))
.withMotionProfileConfig(
new MotionProfileConfig()
.withMaximumVelocity(45) // rotations per second
.withMaximumAcceleration(450) // rotations per second per second
)
.withFeedforwardConfig(
new FeedforwardControllerConfig()
.withStaticFeedforward(0.14) // volts
.withVelocityFeedforward(0.2617) // volts per rotation per second
);

/** Serializer controller. */
private final VelocityControllerIO serializer;

/** Serializer values. */
/** Serializer controller values. */
private final VelocityControllerIOValues serializerValues;

/** Flywheel. */
private final VelocityControllerIO flywheel;
/** Serializer controller acceleration limiter. */
private final SlewRateLimiter serializerAccelerationLimiter;

/** Flywheel values. */
private final VelocityControllerIOValues flywheelValues;
/** Shooter goal. Set by superstructure. */
private ShooterState goal;

private ShooterState setpoint, goal;
/** Shooter setpoint. Updated periodically to reach goal within constraints. */
private ShooterState setpoint;

/** Creates a new instance of the shooter subsystem. */
/** Initializes the shooter subsystem and configures shooter hardware. */
private Shooter() {
serializer = ShooterFactory.createSerializer();
serializerValues = new VelocityControllerIOValues();
serializer.configure();
flywheel = ShooterFactory.createFlywheel(flywheelConfig);
flywheel.configure();

flywheel = ShooterFactory.createFlywheel();
flywheelValues = new VelocityControllerIOValues();
flywheel.configure();

setpoint = ShooterState.IDLE;
goal = ShooterState.IDLE;
flywheelAccelerationLimiter = flywheelConfig.motionProfileConfig().createRateLimiter();

serializer = ShooterFactory.createSerializer(serializerConfig);
serializer.configure();

serializerValues = new VelocityControllerIOValues();

serializerAccelerationLimiter = serializerConfig.motionProfileConfig().createRateLimiter();

setpoint = ShooterState.IDLING;
goal = ShooterState.IDLING;
}

/**
* Gets the instance of the shooter subsystem.
* Returns the shooter subsystem instance.
*
* @return the instance of the shooter subsystem.
* @return the shooter subsystem instance.
*/
public static Shooter getInstance() {
if (instance == null) {
Expand All @@ -57,48 +118,71 @@ public static Shooter getInstance() {

@Override
public void periodic() {
serializer.update(serializerValues);
flywheel.update(flywheelValues);
serializer.update(serializerValues);

setpoint = goal;

double flywheelSetpoint =
FlywheelConstants.ACCELERATION_LIMITER.calculate(
setpoint.flywheelVelocityRotationsPerSecond());
flywheelAccelerationLimiter.calculate(setpoint.flywheelVelocityRotationsPerSecond());
double serializerSetpoint =
SerializerConstants.ACCELERATION_LIMITER.calculate(
setpoint.serializerVelocityRotationsPerSecond());
serializerAccelerationLimiter.calculate(setpoint.serializerVelocityRotationsPerSecond());

flywheel.setSetpoint(flywheelSetpoint);
serializer.setSetpoint(serializerSetpoint);
}

@Override
public void addToShuffleboard(ShuffleboardTab tab) {
VelocityControllerIO.addToShuffleboard(tab, "Serializer", serializerValues);
VelocityControllerIO.addToShuffleboard(tab, "Flywheel", flywheelValues);
VelocityControllerIO.addToShuffleboard(tab, "Serializer", serializerValues);

tab.addBoolean("Serializer Current Spike?", this::serializerCurrentSpike);
}

private boolean serializerCurrentSpike() {
return serializerValues.motorAmps > SerializerConstants.NOTE_AMPS;
}

public Trigger serializedNote() {
return new Trigger(this::serializerCurrentSpike);
}

/**
* Returns the shooter state.
*
* @return the shooter state.
*/
public ShooterState getState() {
return new ShooterState(
flywheelValues.velocityRotationsPerSecond, serializerValues.velocityRotationsPerSecond);
}

/**
* Sets the shooter goal state.
*
* @param goal the shooter goal state.
*/
public void setGoal(ShooterState goal) {
this.goal = goal;
}

/**
* Returns true if the shooter is at the goal state.
*
* @return true if the shooter is at the goal state.
*/
public boolean atGoal() {
return getState().at(goal);
}

/**
* Returns a trigger for if a note is serialized.
*
* @return a trigger for if a note is serialized.
*/
public Trigger serializedNote() {
return new Trigger(this::serializerCurrentSpike);
}

/**
* Returns true if the serializer has a current spike.
*
* @return true if the serializer has a current spike.
*/
private boolean serializerCurrentSpike() {
return serializerValues.motorAmps > 20.0;
}
}
103 changes: 0 additions & 103 deletions src/main/java/frc/robot/shooter/ShooterConstants.java

This file was deleted.

Loading

0 comments on commit 7abd089

Please sign in to comment.