@@ -30,31 +30,21 @@ protected Command getRedAutoCommand() {
30
30
new Pose2d (15.78 , 6.67 , Rotation2d .fromDegrees (-60.48 )))),
31
31
trailblazer .followSegment (
32
32
new AutoSegment (
33
- new AutoPoint (new Pose2d (15.78 , 6.67 , Rotation2d .fromDegrees (-60.48 ))),
34
- new AutoPoint (
35
- new Pose2d (14.676 , 6.767 , Rotation2d .fromDegrees (-26.85 )),
36
- Commands .sequence (
37
- autoCommands .speakerShotWithTimeout (), actions .intakeAssistCommand ())),
38
- new AutoPoint (new Pose2d (13.68 , 6.99 , Rotation2d .fromDegrees (0.0 ))),
39
- new AutoPoint (
40
- new Pose2d (12.64 , 7.06 , Rotation2d .fromDegrees (-21.67 )),
41
- Commands .sequence (
42
- autoCommands .speakerShotWithTimeout (), actions .intakeAssistCommand ())),
43
- new AutoPoint (new Pose2d (8.52 , 7.46 , Rotation2d .fromDegrees (0.0 ))),
44
- new AutoPoint (
45
- new Pose2d (12.64 , 7.06 , Rotation2d .fromDegrees (-21.67 )),
46
- autoCommands .speakerShotWithTimeout ()),
47
- new AutoPoint (
48
- new Pose2d (11.03 , 6.88 , Rotation2d .fromDegrees (30.17 )),
49
- actions .intakeAssistCommand ()),
50
- new AutoPoint (
51
- new Pose2d (10.14 , 6.41 , Rotation2d .fromDegrees (25.43 )),
52
- actions .intakeAssistCommand ()),
53
- new AutoPoint (
54
- new Pose2d (8.32 , 5.79 , Rotation2d .fromDegrees (24.67 )),
55
- actions .intakeAssistCommand ()),
56
- new AutoPoint (
57
- new Pose2d (12.64 , 7.06 , Rotation2d .fromDegrees (-21.67 )),
58
- autoCommands .speakerShotWithTimeout ()))));
33
+ new AutoPoint (new Pose2d (15.78 , 6.67 , Rotation2d .fromDegrees (-60.48 ))))),
34
+ trailblazer .followSegment (
35
+ new AutoSegment (
36
+ new AutoPoint (new Pose2d (14.676 , 6.767 , Rotation2d .fromDegrees (-26.85 ))))),
37
+ autoCommands .speakerShotWithTimeout (),
38
+ actions .intakeAssistCommand (),
39
+ trailblazer .followSegment (
40
+ new AutoSegment (new AutoPoint (new Pose2d (13.68 , 6.99 , Rotation2d .fromDegrees (0.0 ))))),
41
+ trailblazer .followSegment (
42
+ new AutoSegment (
43
+ new AutoPoint (new Pose2d (12.64 , 7.06 , Rotation2d .fromDegrees (-21.67 ))))),
44
+ autoCommands .speakerShotWithTimeout (),
45
+ actions .intakeAssistCommand (),
46
+ trailblazer .followSegment (
47
+ new AutoSegment (new AutoPoint (new Pose2d (8.52 , 7.46 , Rotation2d .fromDegrees (0.0 ))))),
48
+ autoCommands .speakerShotWithTimeout ());
59
49
}
60
50
}
0 commit comments