-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Meg remote-tracking branch origin/staging to tramp
- Loading branch information
Showing
15 changed files
with
860 additions
and
14 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
37 changes: 37 additions & 0 deletions
37
src/main/java/org/team1540/robot2024/subsystems/shooter/FlywheelsIO.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,37 @@ | ||
package org.team1540.robot2024.subsystems.shooter; | ||
|
||
import org.littletonrobotics.junction.AutoLog; | ||
|
||
public interface FlywheelsIO { | ||
@AutoLog | ||
class FlywheelsIOInputs { | ||
public double leftAppliedVolts = 0.0; | ||
public double leftCurrentAmps = 0.0; | ||
public double leftVelocityRPM = 0.0; | ||
|
||
public double rightAppliedVolts = 0.0; | ||
public double rightCurrentAmps = 0.0; | ||
public double rightVelocityRPM = 0.0; | ||
} | ||
|
||
/** | ||
* Updates the set of loggable inputs | ||
*/ | ||
default void updateInputs(FlywheelsIOInputs inputs) {} | ||
|
||
/** | ||
* Runs open loop at the specified voltages | ||
*/ | ||
default void setVoltage(double leftVolts, double rightVolts) {} | ||
|
||
|
||
/** | ||
* Runs closed loop at the specified RPMs | ||
*/ | ||
default void setSpeeds(double leftRPM, double rightRPM) {} | ||
|
||
/** | ||
* Configures the PID controller | ||
*/ | ||
default void configPID(double kP, double kI, double kD) {} | ||
} |
74 changes: 74 additions & 0 deletions
74
src/main/java/org/team1540/robot2024/subsystems/shooter/FlywheelsIOSim.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,74 @@ | ||
package org.team1540.robot2024.subsystems.shooter; | ||
|
||
import edu.wpi.first.math.controller.PIDController; | ||
import edu.wpi.first.math.controller.SimpleMotorFeedforward; | ||
import edu.wpi.first.math.system.plant.DCMotor; | ||
import edu.wpi.first.wpilibj.simulation.FlywheelSim; | ||
import org.team1540.robot2024.Constants; | ||
|
||
import static org.team1540.robot2024.Constants.Shooter.Flywheels.*; | ||
|
||
public class FlywheelsIOSim implements FlywheelsIO{ | ||
private final FlywheelSim leftSim = | ||
new FlywheelSim(DCMotor.getFalcon500(1), GEAR_RATIO, SIM_MOI); | ||
private final FlywheelSim rightSim = | ||
new FlywheelSim(DCMotor.getFalcon500(1), GEAR_RATIO, SIM_MOI); | ||
|
||
private final PIDController rightController = new PIDController(KP, KI, KD); | ||
private final PIDController leftController = new PIDController(KP, KI, KD); | ||
private final SimpleMotorFeedforward feedforward = new SimpleMotorFeedforward(KS, KV); | ||
|
||
private boolean isClosedLoop; | ||
private double leftSetpointRPS; | ||
private double rightSetpointRPS; | ||
|
||
private double leftVolts = 0.0; | ||
private double rightVolts = 0.0; | ||
|
||
@Override | ||
public void updateInputs(FlywheelsIOInputs inputs) { | ||
if (isClosedLoop) { | ||
leftVolts = | ||
leftController.calculate(leftSim.getAngularVelocityRPM() / 60, leftSetpointRPS) | ||
+ feedforward.calculate(leftSetpointRPS); | ||
rightVolts = | ||
rightController.calculate(rightSim.getAngularVelocityRPM() / 60, rightSetpointRPS) | ||
+ feedforward.calculate(rightSetpointRPS); | ||
} | ||
|
||
leftSim.setInputVoltage(leftVolts); | ||
rightSim.setInputVoltage(rightVolts); | ||
leftSim.update(Constants.LOOP_PERIOD_SECS); | ||
rightSim.update(Constants.LOOP_PERIOD_SECS); | ||
|
||
inputs.leftVelocityRPM = leftSim.getAngularVelocityRPM(); | ||
inputs.leftAppliedVolts = leftVolts; | ||
inputs.leftCurrentAmps = leftSim.getCurrentDrawAmps(); | ||
|
||
inputs.rightVelocityRPM = rightSim.getAngularVelocityRPM(); | ||
inputs.rightAppliedVolts = rightVolts; | ||
inputs.rightCurrentAmps = rightSim.getCurrentDrawAmps(); | ||
} | ||
|
||
@Override | ||
public void setVoltage(double leftVolts, double rightVolts) { | ||
isClosedLoop = false; | ||
this.leftVolts = leftVolts; | ||
this.rightVolts = rightVolts; | ||
} | ||
|
||
@Override | ||
public void setSpeeds(double leftRPM, double rightRPM) { | ||
isClosedLoop = true; | ||
leftController.reset(); | ||
rightController.reset(); | ||
leftSetpointRPS = leftRPM / 60; | ||
rightSetpointRPS = rightRPM / 60; | ||
} | ||
|
||
@Override | ||
public void configPID(double kP, double kI, double kD) { | ||
leftController.setPID(kP, kI, kD); | ||
rightController.setPID(kP, kI, kD); | ||
} | ||
} |
Oops, something went wrong.