generated from Frc5572/Java-Template
-
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.
- Loading branch information
1 parent
37b7a05
commit 07d14dd
Showing
2 changed files
with
47 additions
and
3 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
43 changes: 43 additions & 0 deletions
43
src/main/java/frc/robot/subsystems/shooter/ShooterSim.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,43 @@ | ||
package frc.robot.subsystems.shooter; | ||
|
||
import edu.wpi.first.math.MathUtil; | ||
import edu.wpi.first.math.system.plant.DCMotor; | ||
import edu.wpi.first.wpilibj.simulation.FlywheelSim; | ||
import frc.robot.Constants; | ||
|
||
/** | ||
* Class for ShooterSim | ||
*/ | ||
public class ShooterSim implements ShooterIO { | ||
|
||
private FlywheelSim topShooterMotor = | ||
new FlywheelSim(DCMotor.getNeoVortex(1), 1 / Constants.ShooterConstants.GEAR_RATIO, 0.025); | ||
private FlywheelSim bottomShooterMotor = | ||
new FlywheelSim(DCMotor.getNeoVortex(1), 1 / Constants.ShooterConstants.GEAR_RATIO, 0.025); | ||
|
||
private double topAppliedVolts = 0.0; | ||
private double bottomAppliedVolts = 0.0; | ||
|
||
|
||
/** | ||
* Constructor Shooter Subsystem - sets motor and encoder preferences | ||
*/ | ||
public ShooterSim() {} | ||
|
||
public void setTopMotor(double power) { | ||
topAppliedVolts = MathUtil.clamp(power, -12.0, 12.0); | ||
topShooterMotor.setInputVoltage(topAppliedVolts); | ||
} | ||
|
||
public void setBottomMotor(double power) { | ||
bottomAppliedVolts = MathUtil.clamp(power, -12.0, 12.0); | ||
bottomShooterMotor.setInputVoltage(bottomAppliedVolts); | ||
} | ||
|
||
|
||
@Override | ||
public void updateInputs(ShooterIOInputsAutoLogged inputs) { | ||
inputs.topShooterVelocityRotPerMin = topShooterMotor.getAngularVelocityRPM(); | ||
inputs.bottomShooterVelocityRotPerMin = bottomShooterMotor.getAngularVelocityRPM(); | ||
} | ||
} |