Skip to content

Commit

Permalink
Merge pull request #11 from ATAARobotics/Unstable
Browse files Browse the repository at this point in the history
Fix auto i guess
  • Loading branch information
VedaRePowered authored Mar 2, 2022
2 parents d935992 + 209abf0 commit d32064c
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 4 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/AutoPaths.java
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ public AutoPaths() {
ball4Quadrant2Shoot = new AutoCommand(
Arrays.asList(
new Translation2d(meterConversion(6.6570), meterConversion(5.4252)),
new Translation2d(meterConversion(6.1570), meterConversion(6.4252))
new Translation2d(meterConversion(6.1570), meterConversion(6.5752))
),
3.2 * Math.PI / 4
);
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/subsystems/MagazineSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -48,11 +48,11 @@ public void magazineOff() {
}

public boolean bottomDetector() {
return (bottomDetectors[0].getDistanceInches() > 0 && bottomDetectors[0].getDistanceInches() < 3) || (bottomDetectors[1].getDistanceInches() > 0 && bottomDetectors[1].getDistanceInches() < 3);
return (bottomDetectors[0].getDistanceInches() > 0 && bottomDetectors[0].getDistanceInches() < 4) || (bottomDetectors[1].getDistanceInches() > 0 && bottomDetectors[1].getDistanceInches() < 4);
}

public boolean topDetector() {
return (topDetectors[0].getDistanceInches() > 0 && topDetectors[0].getDistanceInches() < 3) || (topDetectors[1].getDistanceInches() > 0 && topDetectors[1].getDistanceInches() < 3);
return (topDetectors[0].getDistanceInches() > 0 && topDetectors[0].getDistanceInches() < 4) || (topDetectors[1].getDistanceInches() > 0 && topDetectors[1].getDistanceInches() < 4);
}

public boolean bottomDetectorOnly() {
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ public void periodic() {

public void autonomousMode() {
lowSpeed = 0.5;
highFarSpeed = 0.8;
highFarSpeed = 0.83;
}

public void teleopMode() {
Expand Down

0 comments on commit d32064c

Please sign in to comment.