|
7 | 7 | import com.spikes2212.util.UnifiedControlMode;
|
8 | 8 | import edu.wpi.first.math.geometry.Pose2d;
|
9 | 9 | import edu.wpi.first.math.geometry.Rotation2d;
|
| 10 | +import edu.wpi.first.math.geometry.Translation2d; |
10 | 11 | import edu.wpi.first.wpilibj.DriverStation;
|
11 | 12 | import edu.wpi.first.wpilibj.RobotController;
|
12 | 13 | import edu.wpi.first.wpilibj2.command.*;
|
|
22 | 23 |
|
23 | 24 | public class Shoot extends ParallelDeadlineGroup {
|
24 | 25 |
|
| 26 | + private static final Pose2d BLUE_SPEAKER_POSE = new Pose2d(new Translation2d(0.52, 5.59), new Rotation2d()); |
| 27 | + private static final Pose2d RED_SPEAKER_POSE = new Pose2d(new Translation2d(16.07, 5.59), new Rotation2d()); |
| 28 | + |
25 | 29 | // formula which translates the distance of the robot from the speaker to the required height to shoot
|
26 | 30 | private static final Function<Double, Double> DISTANCE_TO_HEIGHT = x -> -3.8 * x + 28.8;
|
27 | 31 | private static final double MAX_FORMULA_DISTANCE = 2.285;
|
@@ -73,9 +77,9 @@ public boolean isFinished() {
|
73 | 77 | InstantCommand setSpeakerPoseCommand = new InstantCommand(() -> {
|
74 | 78 | Optional<DriverStation.Alliance> alliance = DriverStation.getAlliance();
|
75 | 79 | if (alliance.isEmpty() || alliance.get() == DriverStation.Alliance.Blue) {
|
76 |
| - speakerPose = new Pose2d(0.52, 5.59, new Rotation2d()); |
| 80 | + speakerPose = BLUE_SPEAKER_POSE; |
77 | 81 | } else {
|
78 |
| - speakerPose = new Pose2d(16.07, 5.59, new Rotation2d()); |
| 82 | + speakerPose = RED_SPEAKER_POSE; |
79 | 83 | }
|
80 | 84 | }
|
81 | 85 | );
|
|
0 commit comments