Skip to content

Commit

Permalink
[Robot] Shifted the target out slightly to improve off-angle shooting
Browse files Browse the repository at this point in the history
This should mean that our shots will no longer hit the wall when aiming from more than ~45 degrees
  • Loading branch information
mvog2501 committed Mar 28, 2024
1 parent 4e6a53a commit dac9a01
Showing 1 changed file with 2 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
Expand All @@ -28,7 +29,7 @@ public enum FlywheelControl {
REVERSE
}

private static final Pose2d blueSpeakerPose = new Pose2d(0, 5.5475, new Rotation2d(0));
private static final Pose2d blueSpeakerPose = new Pose2d(Units.inchesToMeters(6), 5.5475, new Rotation2d(0)); // Opening extends 18" out
private static final Pose2d blueLobZone = new Pose2d(1, 6, new Rotation2d()); // Between the speaker and the amp

private final PivotSubsystem pivot;
Expand Down

0 comments on commit dac9a01

Please sign in to comment.