diff --git a/TeamCode/src/main/java/opmodes/AutoBase.java b/TeamCode/src/main/java/opmodes/AutoBase.java index c3a7c5f..6bbd0f9 100644 --- a/TeamCode/src/main/java/opmodes/AutoBase.java +++ b/TeamCode/src/main/java/opmodes/AutoBase.java @@ -53,7 +53,7 @@ public abstract class AutoBase extends LinearOpMode { this.robot.update(); this.sleep(20); } - + this.sleep(5000); if (isStopRequested()) { return; } diff --git a/TeamCode/src/main/java/opmodes/RedFrontStage.java b/TeamCode/src/main/java/opmodes/RedFrontStage.java index 2f656d1..508ec43 100644 --- a/TeamCode/src/main/java/opmodes/RedFrontStage.java +++ b/TeamCode/src/main/java/opmodes/RedFrontStage.java @@ -11,7 +11,7 @@ import org.firstinspires.ftc.teamcode.util.CenterStageCommon; @Autonomous(name = "RedFrontStage", preselectTeleOp = "MainTeleOp") public class RedFrontStage extends AutoBase { - private final Pose2d rendezvous = new Pose2d(-36, -11); + private final Pose2d rendezvous = new Pose2d(-36, -10); public RedFrontStage() { super( @@ -23,7 +23,7 @@ public class RedFrontStage extends AutoBase { // propLeft will be a reverse of BlueFrontpropRight protected void propLeft() { TrajectorySequenceBuilder builder = this.robot.getTrajectorySequenceBuilder(); - builder.lineToLinearHeading(new Pose2d(-54, -17, Math.toRadians(123))); + builder.lineToLinearHeading(new Pose2d(-58, -17, Math.toRadians(123))); builder.addDisplacementMarker(10, () -> { this.robot.getClaw().setArmPosition(PICKUP_ARM_MIN); });