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

Commit 9e6dd44

Browse files
committed
fix coordinates in OP auto
1 parent 3ea8f35 commit 9e6dd44

File tree

1 file changed

+10
-9
lines changed

1 file changed

+10
-9
lines changed

src/main/java/frc/robot/autos/amp/Op345Auto.java

Lines changed: 10 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -27,28 +27,29 @@ protected Command getRedAutoCommand() {
2727
Commands.runOnce(
2828
() ->
2929
robotManager.localization.resetPose(
30-
new Pose2d(15.811, 6.713, new Rotation2d(-170.80)))),
30+
new Pose2d(15.78, 6.67, new Rotation2d(-58.39)))),
3131
trailblazer.followSegment(
3232
new AutoSegment(
33-
new AutoPoint(new Pose2d(15.811, 6.713, new Rotation2d(-170.80))),
33+
new AutoPoint(new Pose2d(15.78, 6.67, new Rotation2d(-58.39))),
3434
new AutoPoint(
3535
new Pose2d(14.676, 6.767, new Rotation2d(-26.85)),
3636
Commands.sequence(
3737
autoCommands.speakerShotWithTimeout(), actions.intakeAssistCommand())),
38-
new AutoPoint(new Pose2d(13.959, 6.872, new Rotation2d())),
38+
new AutoPoint(new Pose2d(13.68, 6.99, new Rotation2d(0.0))),
3939
new AutoPoint(
40-
new Pose2d(12.64, 7.063, new Rotation2d()),
40+
new Pose2d(12.64, 7.06, new Rotation2d(-21.67)),
4141
Commands.sequence(
4242
autoCommands.speakerShotWithTimeout(), actions.intakeAssistCommand())),
43-
new AutoPoint(new Pose2d(8.605, 7.449, new Rotation2d(0.0))),
43+
new AutoPoint(new Pose2d(8.52, 7.46, new Rotation2d(0.0))),
4444
new AutoPoint(
45-
new Pose2d(12.64, 7.063, new Rotation2d(-8.0)),
45+
new Pose2d(12.64, 7.06, new Rotation2d(-21.67)),
4646
autoCommands.speakerShotWithTimeout()),
4747
new AutoPoint(
48-
new Pose2d(11.033, 6.879, new Rotation2d()), actions.intakeAssistCommand()),
49-
new AutoPoint(new Pose2d(10.827, 6.42, new Rotation2d())),
48+
new Pose2d(11.03, 6.88, new Rotation2d(30.17)), actions.intakeAssistCommand()),
49+
new AutoPoint(new Pose2d(10.14, 6.41, new Rotation2d(25.43)), actions.intakeAssistCommand()),
50+
new AutoPoint(new Pose2d(8.32, 8.32, new Rotation2d(24.67)), actions.intakeAssistCommand()),
5051
new AutoPoint(
51-
new Pose2d(12.553, 6.036, new Rotation2d(-8.0)),
52+
new Pose2d(12.64, 7.06, new Rotation2d(-21.67)),
5253
autoCommands.speakerShotWithTimeout()))));
5354
}
5455
}

0 commit comments

Comments
 (0)