Skip to content

Commit

Permalink
Fixed
Browse files Browse the repository at this point in the history
  • Loading branch information
Strflightmight09 committed Oct 6, 2024
1 parent 1c68483 commit 3013589
Showing 1 changed file with 9 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@
import java.util.function.DoubleSupplier;

public class GearRatioCalculationCommand extends Command {
private static final LoggedDashboardNumber MOVEMENT_VOLTAGE = new LoggedDashboardNumber("GearRatioCalculation/Voltage", 1);
private static final LoggedDashboardBoolean SHOULD_MOVE_CLOCKWISE = new LoggedDashboardBoolean("GearRatioCalculation/ShouldMoveClockwise", false);
private final LoggedDashboardNumber MOVEMENT_VOLTAGE;
private final LoggedDashboardBoolean SHOULD_MOVE_CLOCKWISE;

private final DoubleSupplier rotorPositionSupplier;
private final DoubleSupplier encoderPositionSupplier;
Expand All @@ -26,9 +26,11 @@ public GearRatioCalculationCommand(DoubleSupplier rotorPositionSupplier, DoubleS
this.rotorPositionSupplier = rotorPositionSupplier;
this.encoderPositionSupplier = encoderPositionSupplier;
this.runGearRatioCalculation = runGearRatioCalculation;
this.subsystemName = repeatedly().getName();
this.subsystemName = requirement.getName();

addRequirements(requirement);
MOVEMENT_VOLTAGE = new LoggedDashboardNumber("GearRatioCalculation/" + subsystemName + "/Voltage", 1);
SHOULD_MOVE_CLOCKWISE = new LoggedDashboardBoolean("GearRatioCalculation/" + subsystemName + "/ShouldMoveClockwise", false);
}

@Override
Expand All @@ -42,9 +44,9 @@ public void execute() {
runGearRatioCalculation.accept(MOVEMENT_VOLTAGE.get() * getRotationDirection());
gearRatio = calculateGearRatio();

Logger.recordOutput(subsystemName + "GearRatioCalculation/RotorDistance", getRotorDistance());
Logger.recordOutput(subsystemName + "GearRatioCalculation/EncoderDistance", getEncoderDistance());
Logger.recordOutput(subsystemName + "GearRatioCalculation/GearRatio", gearRatio);
Logger.recordOutput("GearRatioCalculation/" + subsystemName + "/RotorDistance", getRotorDistance());
Logger.recordOutput("GearRatioCalculation/" + subsystemName + "/EncoderDistance", getEncoderDistance());
Logger.recordOutput("GearRatioCalculation/" + subsystemName + "/GearRatio", gearRatio);
}

@Override
Expand Down

0 comments on commit 3013589

Please sign in to comment.