Skip to content
This repository was archived by the owner on Jun 20, 2025. It is now read-only.

Commit 671b55a

Browse files
committed
fix: made gear ratios non-zero
1 parent 33b1517 commit 671b55a

File tree

3 files changed

+7
-6
lines changed

3 files changed

+7
-6
lines changed

src/main/java/org/team1540/robot2024/Constants.java

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -56,15 +56,16 @@ public static class Drivetrain {
5656
public static final double MAX_ANGULAR_SPEED = MAX_LINEAR_SPEED / DRIVE_BASE_RADIUS;
5757
}
5858
public static class Indexer {
59+
// TODO: fix these constants
5960
public static final int INTAKE_ID = 0;
6061
public static final int FEEDER_ID = 0;
6162
public static final double FEEDER_KP = 0.0;
6263
public static final double FEEDER_KI = 0.0;
6364
public static final double FEEDER_KD = 0.0;
6465
public static final double FEEDER_KS = 0.0;
6566
public static final double FEEDER_KV = 0.0;
66-
public static final double FEEDER_GEAR_RATIO = 0.0;
67-
public static final double INTAKE_GEAR_RATIO = 0.0;
67+
public static final double FEEDER_GEAR_RATIO = 1.0;
68+
public static final double INTAKE_GEAR_RATIO = 1.0;
6869

6970
}
7071
}

src/main/java/org/team1540/robot2024/subsystems/indexer/IndexerIO.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@ class IndexerIOInputs {
1212
public double feederVoltage;
1313
public double feederCurrentAmps;
1414
public double feederVelocityRPM;
15-
public boolean noteInIntake;
15+
public boolean noteInIntake = false;
1616
}
1717

1818
/**

src/main/java/org/team1540/robot2024/subsystems/indexer/IndexerIOSim.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@ public class IndexerIOSim implements IndexerIO {
1414

1515
private final DCMotorSim intakeSim = new DCMotorSim(DCMotor.getNEO(1), INTAKE_GEAR_RATIO,0.025);
1616
private final DCMotorSim feederSim = new DCMotorSim(DCMotor.getNEO(1), FEEDER_GEAR_RATIO,0.025);
17-
private final SimDeviceSim beamBreakSim = new SimDeviceSim("Indexer Beam Break");
17+
// private final SimDeviceSim beamBreakSim = new SimDeviceSim("Indexer Beam Break");
1818
private final PIDController feederSimPID = new PIDController(FEEDER_KP, FEEDER_KI,FEEDER_KD);
1919

2020
@Override
@@ -27,10 +27,10 @@ public void updateInputs(IndexerIOInputs inputs) {
2727
inputs.feederCurrentAmps = feederSim.getCurrentDrawAmps();
2828
// inputs.feederVoltage = feederSim.getBusVoltage() * feederSim.getAppliedOutput();
2929
inputs.feederVelocityRPM = feederSim.getAngularVelocityRPM();
30-
inputs.noteInIntake = beamBreakSim.getBoolean("Indexer Beam Break").get();
30+
// inputs.noteInIntake = beamBreakSim.getBoolean("Indexer Beam Break").get();
3131

3232
// this is a very funny line of code, and absolutely does not belong here, but I don't know how to do this otherwise
33-
feederSim.setState(feederSim.getAngularPositionRad(), feederSimPID.calculate(feederSim.getAngularVelocityRadPerSec()));
33+
feederSim.setState(feederSim.getAngularPositionRad(), feederSimPID.calculate(feederSim.getAngularVelocityRadPerSec()));
3434

3535
}
3636

0 commit comments

Comments
 (0)