Skip to content

Commit

Permalink
fix shooter code
Browse files Browse the repository at this point in the history
  • Loading branch information
elsaroni committed Oct 17, 2024
1 parent ea1e3c6 commit 5035ef4
Show file tree
Hide file tree
Showing 4 changed files with 56 additions and 107 deletions.
1 change: 0 additions & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@ public class Robot extends LoggedRobot {
*/
@Override
public void robotInit() {
// Record metadata
Logger.recordMetadata("ProjectName", BuildConstants.MAVEN_NAME);
Logger.recordMetadata("BuildDate", BuildConstants.BUILD_DATE);
Logger.recordMetadata("GitSHA", BuildConstants.GIT_SHA);
Expand Down
18 changes: 8 additions & 10 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,19 +5,17 @@
public interface ShooterIO {
@AutoLog
public static class ShooterIOInputs {
public double leftMotorVelocity = 0.0;
public double rightMotorVelocity = 0.0;
public double leftAppliedVolts = 0.0;
public double rightAppliedVolts = 0.0;
public double leftOutputCurrent = 0.0;
public double rightOutputCurrent = 0.0;
public double topMotorVelocity = 0.0;
public double bottomMotorVelocity = 0.0;
public double topAppliedVolts = 0.0;
public double bottomAppliedVolts = 0.0;
public double topOutputCurrent = 0.0;
public double bottomOutputCurrent = 0.0;
}

public default void spinForwards() {}
public default void setVoltage(double voltage) {}

public default void spinBackwards() {}

public default void stopMotor() {}
public default void setVelocity(double velocity) {}

public default void updateInputs(ShooterIOInputs inputs) {}
}
81 changes: 27 additions & 54 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIOReal.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,78 +4,51 @@
import com.revrobotics.CANSparkFlex;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.RelativeEncoder;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;

public class ShooterIOReal implements ShooterIO {
private CANSparkFlex leftShooterMotor =
private CANSparkFlex topShooterMotor =
new CANSparkFlex(0, MotorType.kBrushless); // Can IDs not accurate
private CANSparkFlex rightShooterMotor =
private CANSparkFlex bottomShooterMotor =
new CANSparkFlex(1, MotorType.kBrushless); // Can IDsp not accurate

private RelativeEncoder leftShooterEncoder = leftShooterMotor.getEncoder();
private RelativeEncoder rightShooterEncoder = rightShooterMotor.getEncoder();
private RelativeEncoder topShooterEncoder = topShooterMotor.getEncoder();
private RelativeEncoder bottomShooterEncoder = bottomShooterMotor.getEncoder();
private SimpleMotorFeedforward ffmodel = new SimpleMotorFeedforward(0, 0);

public ShooterIOReal() {
rightShooterMotor.restoreFactoryDefaults();
leftShooterMotor.restoreFactoryDefaults();
bottomShooterMotor.restoreFactoryDefaults();
topShooterMotor.restoreFactoryDefaults();

rightShooterMotor.follow(leftShooterMotor, true);
bottomShooterMotor.follow(topShooterMotor, true);

leftShooterMotor.setSmartCurrentLimit(40);
rightShooterMotor.setSmartCurrentLimit(40);
topShooterMotor.setSmartCurrentLimit(40);
bottomShooterMotor.setSmartCurrentLimit(40);

rightShooterMotor.setIdleMode(IdleMode.kCoast);
leftShooterMotor.setIdleMode(IdleMode.kCoast);
bottomShooterMotor.setIdleMode(IdleMode.kCoast);
topShooterMotor.setIdleMode(IdleMode.kCoast);

rightShooterMotor.burnFlash();
leftShooterMotor.burnFlash();
bottomShooterMotor.burnFlash();
topShooterMotor.burnFlash();
}

@Override
public void spinForwards() {
leftShooterMotor.set(1.0);
public void setVoltage(double voltage) {
topShooterMotor.setVoltage(voltage);
}

@Override
public void spinBackwards() {
leftShooterMotor.set(-1.0);
}

@Override
public void stopMotor() {
leftShooterMotor.set(0.0);
}

public double getLeftvelocity() {
return leftShooterEncoder.getVelocity();
}

public double getRightvelocity() {
return rightShooterEncoder.getVelocity();
}

public double getLeftVoltage() {
return leftShooterMotor.getBusVoltage();
}

public double getRightVoltage() {
return rightShooterMotor.getBusVoltage();
}

public double getLeftCurrent() {
return leftShooterMotor.getOutputCurrent();
}

public double getRightCurrent() {
return rightShooterMotor.getOutputCurrent();
public void setVelocity(double velocity) {
topShooterMotor.setVoltage(ffmodel.calculate(velocity));
}

@Override
public void updateInputs(ShooterIOInputs inputs) {
inputs.leftMotorVelocity = getLeftvelocity();
inputs.rightMotorVelocity = getRightvelocity();
inputs.leftAppliedVolts = getLeftVoltage();
inputs.rightAppliedVolts = getRightVoltage();
inputs.leftOutputCurrent = getLeftCurrent();
inputs.rightOutputCurrent = getRightCurrent();
}
}
inputs.topMotorVelocity = topShooterEncoder.getVelocity();
inputs.bottomMotorVelocity = bottomShooterEncoder.getVelocity();
inputs.topAppliedVolts = topShooterMotor.getBusVoltage();
inputs.bottomAppliedVolts = bottomShooterMotor.getBusVoltage();
inputs.topOutputCurrent = topShooterMotor.getOutputCurrent();
inputs.bottomOutputCurrent = bottomShooterMotor.getOutputCurrent();
}
}
63 changes: 21 additions & 42 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIOSim.java
Original file line number Diff line number Diff line change
@@ -1,58 +1,37 @@
//thomas jin fix this
//i just copy pasta from flywheel sim
//type shi pray emoji
// thomas jin fix this
// i just copy pasta from flywheel sim
// type shi pray emoji
package frc.robot.subsystems.shooter;

import edu.wpi.first.math.MathUtil;
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 edu.wpi.first.wpilibj.simulation.DCMotorSim;

public class FlywheelIOSim implements FlywheelIO {
private FlywheelSim sim = new FlywheelSim(DCMotor.getNEO(1), 1.5, 0.004);
private PIDController pid = new PIDController(0.0, 0.0, 0.0);

private boolean closedLoop = false;
private double ffVolts = 0.0;
public class ShooterIOSim implements ShooterIO {
private DCMotorSim sim = new DCMotorSim(DCMotor.getNEO(1), 1.5, 0.004);
private double appliedVolts = 0.0;
private SimpleMotorFeedforward ffmodel = new SimpleMotorFeedforward(0, 0);

@Override
public void updateInputs(FlywheelIOInputs inputs) {
if (closedLoop) {
appliedVolts =
MathUtil.clamp(pid.calculate(sim.getAngularVelocityRadPerSec()) + ffVolts, -12.0, 12.0);
sim.setInputVoltage(appliedVolts);
}

sim.update(0.02);

inputs.positionRad = 0.0;
inputs.velocityRadPerSec = sim.getAngularVelocityRadPerSec();
inputs.appliedVolts = appliedVolts;
inputs.currentAmps = new double[] {sim.getCurrentDrawAmps()};
}

@Override
public void setVoltage(double volts) {
closedLoop = false;
appliedVolts = volts;
sim.setInputVoltage(volts);
public void setVoltage(double voltage) {
appliedVolts = voltage;
sim.setInputVoltage(voltage);
}

@Override
public void setVelocity(double velocityRadPerSec, double ffVolts) {
closedLoop = true;
pid.setSetpoint(velocityRadPerSec);
this.ffVolts = ffVolts;
public void setVelocity(double velocity) {
setVoltage(ffmodel.calculate(velocity));
}

@Override
public void stop() {
setVoltage(0.0);
}
public void updateInputs(ShooterIOInputs inputs) {
sim.update(0.02);

@Override
public void configurePID(double kP, double kI, double kD) {
pid.setPID(kP, kI, kD);
inputs.topMotorVelocity = sim.getAngularVelocityRPM();
inputs.bottomMotorVelocity = sim.getAngularVelocityRPM();
inputs.topAppliedVolts = appliedVolts;
inputs.bottomAppliedVolts = appliedVolts;
inputs.topOutputCurrent = sim.getCurrentDrawAmps();
inputs.bottomOutputCurrent = sim.getCurrentDrawAmps();
}
}

0 comments on commit 5035ef4

Please sign in to comment.