Skip to content

Commit

Permalink
shooter fix eeelsa
Browse files Browse the repository at this point in the history
  • Loading branch information
Bob1272001 committed Oct 8, 2024
1 parent 1ee0be2 commit d4c7b9f
Show file tree
Hide file tree
Showing 2 changed files with 21 additions and 9 deletions.
7 changes: 6 additions & 1 deletion src/main/java/frc/robot/subsystems/shooter/ShooterIO.java
Original file line number Diff line number Diff line change
@@ -1,18 +1,23 @@
package frc.robot.subsystems.shooter;

import frc.robot.subsystems.shooter.ShooterIO.ShooterIOInputs;
import org.littletonrobotics.junction.AutoLog;

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 default void spinForwards() {}

public default void spinBackwards() {}

public default void stopMotor() {}

public default void updateInputs(ShooterIOInputs inputs) {}
}
23 changes: 15 additions & 8 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIOReal.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package frc.robot.subsystems.shooter;

import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkFlex;
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.RelativeEncoder;
Expand All @@ -9,15 +10,22 @@ public class ShooterIOReal implements ShooterIO {
new CANSparkFlex(0, MotorType.kBrushless); // Can IDs not accurate
private CANSparkFlex rightShooterMotor =
new CANSparkFlex(1, MotorType.kBrushless); // Can IDsp not accurate

private RelativeEncoder leftShooterEncoder = leftShooterMotor.getEncoder();
private RelativeEncoder rightShooterEncoder = rightShooterMotor.getEncoder();

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

rightShooterMotor.follow(leftShooterMotor, true);

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

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

rightShooterMotor.burnFlash();
leftShooterMotor.burnFlash();
}
Expand Down Expand Up @@ -50,25 +58,24 @@ public double getLeftVoltage() {
}

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

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

public double getRightCurrent() {
return rightShooterMotor.getOutputCurrent();
return rightShooterMotor.getOutputCurrent();
}

@Override
public void updateInputs(ShooterIOInputs inputs) {
inputs.leftMotorVelocity = getLeftvelocity();
inputs.rightMotorVelocity = getRightvelocity();
inputs.leftAppliedVolts = getLeftVoltage();
inputs.leftAppliedVolts = getLeftVoltage();
inputs.rightAppliedVolts = getRightVoltage();
inputs.leftOutputCurrent = getLeftCurrent();
inputs.leftOutputCurrent = getLeftCurrent();
inputs.rightOutputCurrent = getRightCurrent();
}
}

}

0 comments on commit d4c7b9f

Please sign in to comment.