Skip to content

Commit

Permalink
various bug fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
24cirinom committed Feb 19, 2024
1 parent d04a6a5 commit abd7da9
Show file tree
Hide file tree
Showing 4 changed files with 7 additions and 11 deletions.
10 changes: 6 additions & 4 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,8 @@
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;
import org.littletonrobotics.junction.networktables.LoggedDashboardNumber;

// import wristcommands

/**
* This class is where the bulk of the robot should be declared. Since Command-based is a
* "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot}
Expand Down Expand Up @@ -221,11 +223,11 @@ private void configureButtonBindings() {
operatorController
.a()
.whileTrue(
Commands.startEnd(() -> sClimber.runTargetPosition(0.5), sClimber::stop, sClimber));
Commands.startEnd(() -> sClimber.runTargetPosition(0), sClimber::stop, sClimber));
operatorController
.a()
.whileFalse(
Commands.startEnd(() -> sClimber.runTargetPosition(0.7), sClimber::stop, sClimber));
.b()
.whileTrue(
Commands.startEnd(() -> sClimber.runTargetPosition(0.55), sClimber::stop, sClimber));
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,4 @@ public default void stop() {}
public default void configurePID(double kP, double kI, double kD) {}

public default void setTargetDistance(double distance) {}


}
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,6 @@ public void updateInputs(ArmElevatorIOInputs inputs) {
inputs.targetDistance = targetDistance;
inputs.currentAmps = new double[] {motor.getOutputCurrent()};

System.out.println(encoder.getPosition() / GEAR_RATIO * PULLEY_CIRCUMFERENCE);
}

@Override
Expand Down Expand Up @@ -92,7 +91,7 @@ public void configurePID(double kP, double kI, double kD) {
}

@Override
public void setTargetDistance(double distanceInches) {
public void setTargetDistance(double distanceMeters) {
targetDistance = distanceMeters;
pid.setReference(
distanceMeters / PULLEY_CIRCUMFERENCE * GEAR_RATIO,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,9 +48,6 @@ public ClimberIOSparkMax() {
leftMotor.setCANTimeout(250);
rightMotor.setCANTimeout(250);

leftRelativeEncoder.setPosition(ClimberConstants.initialPosition);
rightRelativeEncoder.setPosition(ClimberConstants.initialPosition);

leftMotor.setInverted(true);

leftMotor.enableVoltageCompensation(12.0);
Expand Down

0 comments on commit abd7da9

Please sign in to comment.