-
Notifications
You must be signed in to change notification settings - Fork 12
/
FarRight5BallPlus1.java
95 lines (82 loc) · 4.05 KB
/
FarRight5BallPlus1.java
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
package com.team254.frc2022.auto.modes;
import com.team254.frc2022.auto.AutoModeEndedException;
import com.team254.frc2022.auto.actions.*;
import com.team254.frc2022.paths.TrajectoryGenerator;
import com.team254.frc2022.subsystems.Superstructure;
import com.team254.lib.geometry.Pose2d;
import com.team254.lib.geometry.Rotation2d;
import java.util.Optional;
public class FarRight5BallPlus1 extends AutoModeBase {
public FarRight5BallPlus1() {
mStartPose = new Pose2d(0, 0, Rotation2d.fromDegrees(90));
}
@Override
protected void routine() throws AutoModeEndedException {
runAction(new HintTurretAction(Optional.of(Rotation2d.fromDegrees(90))));
runAction(new OrientModulesAction(0.75, Rotation2d.fromDegrees(0)));
Superstructure.getInstance().setAimingGoal(Rotation2d.fromDegrees(160.0));
Superstructure.getInstance().setEjectConstraints(6, 5.5);
runAction(
new ParallelAction(
new DriveTrajectoryAction(TrajectoryGenerator.getInstance().getTrajectorySet().farRightStartToFarRightBallEject, true),
new SeriesAction(
new WaitAction(1.0),
new RunIntakeAction(false),
new WaitAction(0.75),
new StowIntakeAction(false),
new WaitAction(1.0)
)
)
);
runAction(new HintTurretAction(Optional.empty()));
runAction(
new ParallelAction(
new SeriesAction(
new RunIntakeAction(true),
new WaitAction(1.2),
new StowIntakeAction(true, true, false)
),
new SeriesAction(
new WaitAction(0.05),
new DriveTrajectoryAction(TrajectoryGenerator.getInstance().getTrajectorySet().farRightBallEjectToCloseRightBall)
),
new SeriesAction(
new WaitAction(2.5),
new ParallelAction(
new ShootAction(1.75),
new SeriesAction(
new WaitAction(0.4),
new RunIntakeAction(true),
new WaitAction(0.4),
new StowIntakeAction(true, false, true),
new WaitAction(0.5)
)
)
)
)
);
runAction(
new ParallelAction(
new SuperstructureIdleAction(),
new RunIntakeAction(true),
new DriveTrajectoryAction(TrajectoryGenerator.getInstance().getTrajectorySet().closeRightBallToHPRebound)
)
);
runAction(new DriveTrajectoryAction(TrajectoryGenerator.getInstance().getTrajectorySet().HPToFeedRebound));
// WaitForNumBannerSensorsAction for 2 balls
runAction(new WaitForNumBannerSensorsAction(2,0.8));
// drive to rebound point and leave intake out
runAction(
new ParallelAction(
new SeriesAction(
new StowIntakeAction(true, false), // dislodge ball if it gets stuck in intake
new WaitAction(1.0),
new RunIntakeAction(false)
),
new DriveTrajectoryAction(TrajectoryGenerator.getInstance().getTrajectorySet().feedToCloseRebound),
new HintTurretAction(Optional.of(Rotation2d.fromDegrees(20))) // overshoot a bit to make sure turret hits goal
)
);
runAction(new ShootAction(5.0, false));
}
}