Skip to content

Commit

Permalink
this should be all other than inputs classes
Browse files Browse the repository at this point in the history
  • Loading branch information
GearBoxFox committed Jan 20, 2024
1 parent bc8bc25 commit 1d4d4d9
Show file tree
Hide file tree
Showing 8 changed files with 156 additions and 109 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ public void print() {

DriverStation.reportWarning("FF Characterization Results:", false);
DriverStation.reportWarning("\tCount=" + Integer.toString(velocityData.size()) + "", false);
DriverStation.reportWarning(String.format("\tR2=%.5f", regression.R2()), false);
DriverStation.reportWarning(String.format("\tR2=%.5f", regression.r2()), false);
DriverStation.reportWarning(String.format("\tkS=%.5f", regression.beta(0)), false);
DriverStation.reportWarning(String.format("\tkV=%.5f", regression.beta(1)), false);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ public class ModuleIOSparkMax implements ModuleIO {
private final Queue<Double> drivePositionQueue;
private final Queue<Double> turnPositionQueue;

private final boolean isTurnMotorInverted = true;
private static final boolean TURN_MOTOR_INVERTED = true;
private final Rotation2d absoluteEncoderOffset;

public ModuleIOSparkMax(int index) {
Expand Down Expand Up @@ -80,7 +80,7 @@ public ModuleIOSparkMax(int index) {
absoluteEncoderOffset = new Rotation2d(0.0); // MUST BE CALIBRATED
break;
default:
throw new RuntimeException("Invalid module index");
throw new UnsupportedOperationException("Invalid module index");
}

driveSparkMax.restoreFactoryDefaults();
Expand All @@ -92,7 +92,7 @@ public ModuleIOSparkMax(int index) {
driveEncoder = driveSparkMax.getEncoder();
turnRelativeEncoder = turnSparkMax.getEncoder();

turnSparkMax.setInverted(isTurnMotorInverted);
turnSparkMax.setInverted(TURN_MOTOR_INVERTED);
driveSparkMax.setSmartCurrentLimit(40);
turnSparkMax.setSmartCurrentLimit(30);
driveSparkMax.enableVoltageCompensation(12.0);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
* absolute encoders using AdvantageScope. These values are logged under
* "/Drive/ModuleX/TurnAbsolutePositionRad"
*/

public class ModuleIOTalonFX implements ModuleIO {
private final TalonFX m_driveTalon;
private final TalonFX m_turnTalon;
Expand Down
16 changes: 7 additions & 9 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,14 +3,12 @@
import org.littletonrobotics.junction.AutoLog;

public interface ShooterIO {

@AutoLog
class ShooterIOInputs {
}
default void setMotorVoltageTL(double voltage) {}
default void setMotorVoltageTR(double voltage) {}
default void setMotorVoltageBL(double voltage) {}
default void setMotorVoltageBR(double voltage) {}
default void setKickerVoltage(double voltage) {}
@AutoLog
class ShooterIOInputs {}
default void setMotorVoltageTL(double voltage) {}
default void setMotorVoltageTR(double voltage) {}
default void setMotorVoltageBL(double voltage) {}
default void setMotorVoltageBR(double voltage) {}
default void setKickerVoltage(double voltage) {}

}
86 changes: 43 additions & 43 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIOPrototype.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,47 +5,47 @@
import com.revrobotics.CANSparkMax;

public class ShooterIOPrototype implements ShooterIO {
private final CANSparkFlex m_topLeftMotor;
private final CANSparkFlex m_topRightMotor;
private final CANSparkMax m_bottomLeftMotor;
private final CANSparkMax m_bottomRightMotor;
private final CANSparkMax m_kickekMotor;
public ShooterIOPrototype() {
m_topLeftMotor = new CANSparkFlex(13, CANSparkLowLevel.MotorType.kBrushless);
m_topRightMotor = new CANSparkFlex(14, CANSparkLowLevel.MotorType.kBrushless);
m_bottomLeftMotor = new CANSparkMax(15, CANSparkLowLevel.MotorType.kBrushless);
m_bottomRightMotor = new CANSparkMax(16, CANSparkLowLevel.MotorType.kBrushless);
m_kickekMotor = new CANSparkMax(17, CANSparkLowLevel.MotorType.kBrushless);

m_topLeftMotor.setInverted(false);
m_bottomLeftMotor.setInverted(true);

m_topLeftMotor.burnFlash();
m_topRightMotor.burnFlash();
}

@Override
public void setMotorVoltageTL(double voltage) {
m_topLeftMotor.setVoltage(voltage);
}

@Override
public void setMotorVoltageTR(double voltage) {
m_topRightMotor.setVoltage(voltage);
}

@Override
public void setMotorVoltageBL(double voltage) {
m_bottomLeftMotor.setVoltage(voltage);
}

@Override
public void setMotorVoltageBR(double voltage) {
m_bottomRightMotor.setVoltage(voltage);
}

@Override
public void setKickerVoltage(double voltage) {
m_kickekMotor.setVoltage(voltage);
}
private final CANSparkFlex m_topLeftMotor;
private final CANSparkFlex m_topRightMotor;
private final CANSparkMax m_bottomLeftMotor;
private final CANSparkMax m_bottomRightMotor;
private final CANSparkMax m_kickekMotor;
public ShooterIOPrototype() {
m_topLeftMotor = new CANSparkFlex(13, CANSparkLowLevel.MotorType.kBrushless);
m_topRightMotor = new CANSparkFlex(14, CANSparkLowLevel.MotorType.kBrushless);
m_bottomLeftMotor = new CANSparkMax(15, CANSparkLowLevel.MotorType.kBrushless);
m_bottomRightMotor = new CANSparkMax(16, CANSparkLowLevel.MotorType.kBrushless);
m_kickekMotor = new CANSparkMax(17, CANSparkLowLevel.MotorType.kBrushless);

m_topLeftMotor.setInverted(false);
m_bottomLeftMotor.setInverted(true);

m_topLeftMotor.burnFlash();
m_topRightMotor.burnFlash();
}

@Override
public void setMotorVoltageTL(double voltage) {
m_topLeftMotor.setVoltage(voltage);
}

@Override
public void setMotorVoltageTR(double voltage) {
m_topRightMotor.setVoltage(voltage);
}

@Override
public void setMotorVoltageBL(double voltage) {
m_bottomLeftMotor.setVoltage(voltage);
}

@Override
public void setMotorVoltageBR(double voltage) {
m_bottomRightMotor.setVoltage(voltage);
}

@Override
public void setKickerVoltage(double voltage) {
m_kickekMotor.setVoltage(voltage);
}
}
60 changes: 31 additions & 29 deletions src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,34 +6,36 @@
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class ShooterSubsystem extends SubsystemBase {
private final ShooterIO m_io;
public ShooterSubsystem(ShooterIO io) {
m_io = io;
SmartDashboard.putNumber("Top wheel ratio", 0.8);
SmartDashboard.putNumber("Left wheel", 0.6);
SmartDashboard.putNumber("Right wheel", 0.6);
}

public void setShooterPowerLeft(double power) {
m_io.setMotorVoltageTL((power * 12.0) * SmartDashboard.getNumber("Top wheel ratio", 0.85));
m_io.setMotorVoltageBL(power * 12.0);
}

public void setShooterPowerRight(double power) {
m_io.setMotorVoltageTR((power * 12.0) * SmartDashboard.getNumber("Top wheel ratio", 0.85));
m_io.setMotorVoltageBR(power * 12.0);
}

public void setKickerPower(double power) {
m_io.setKickerVoltage(power * 12.0);
}

public Command setShooterPower(double left, double right) {
return run(() -> {
setShooterPowerLeft(left == 0.0 ? 0.0 : SmartDashboard.getNumber("Left wheel", 0.6));
setShooterPowerRight(right == 0.0 ? 0.0 : SmartDashboard.getNumber("Right wheel", 0.6));
setKickerPower(left == 0.0 ? 0.0 : 1.0);
});
}
private final ShooterIO m_io;

private static final String TOP_WHEEL_RATIO = "Top wheel ratio";
public ShooterSubsystem(ShooterIO io) {
m_io = io;
SmartDashboard.putNumber(TOP_WHEEL_RATIO, 0.8);
SmartDashboard.putNumber("Left wheel", 0.6);
SmartDashboard.putNumber("Right wheel", 0.6);
}

public void setShooterPowerLeft(double power) {
m_io.setMotorVoltageTL((power * 12.0) * SmartDashboard.getNumber(TOP_WHEEL_RATIO, 0.85));
m_io.setMotorVoltageBL(power * 12.0);
}

public void setShooterPowerRight(double power) {
m_io.setMotorVoltageTR((power * 12.0) * SmartDashboard.getNumber(TOP_WHEEL_RATIO, 0.85));
m_io.setMotorVoltageBR(power * 12.0);
}

public void setKickerPower(double power) {
m_io.setKickerVoltage(power * 12.0);
}

public Command setShooterPower(double left, double right) {
return run(() -> {
setShooterPowerLeft(left == 0.0 ? 0.0 : SmartDashboard.getNumber("Left wheel", 0.6));
setShooterPowerRight(right == 0.0 ? 0.0 : SmartDashboard.getNumber("Right wheel", 0.6));
setKickerPower(left == 0.0 ? 0.0 : 1.0);
});
}
}

6 changes: 3 additions & 3 deletions src/main/java/frc/robot/util/LocalADStarAK.java
Original file line number Diff line number Diff line change
Expand Up @@ -100,9 +100,9 @@ public void setDynamicObstacles(
}

private static class ADStarIO implements LoggableInputs {
public LocalADStar adStar = new LocalADStar();
public boolean isNewPathAvailable = false;
public List<PathPoint> currentPathPoints = Collections.emptyList();
protected LocalADStar adStar = new LocalADStar();
protected boolean isNewPathAvailable = false;
protected List<PathPoint> currentPathPoints = Collections.emptyList();

@Override
public void toLog(LogTable table) {
Expand Down
Loading

0 comments on commit 1d4d4d9

Please sign in to comment.