From 05e284b59fe1ccc04248e97d94246a5772e06c62 Mon Sep 17 00:00:00 2001 From: robotics1 Date: Tue, 19 Nov 2024 15:40:16 -0800 Subject: [PATCH] Working Pre loaded auto! Can score 11 points consistently! --- .../firstinspires/ftc/teamcode/PreLoadedBlueBasketAuto.java | 2 ++ .../org/firstinspires/ftc/teamcode/configs/RobotConstants.java | 2 ++ .../ftc/teamcode/subsystem/LiftActionsSubsystem.java | 3 ++- 3 files changed, 6 insertions(+), 1 deletion(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PreLoadedBlueBasketAuto.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PreLoadedBlueBasketAuto.java index 4590249..ae887e6 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PreLoadedBlueBasketAuto.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/PreLoadedBlueBasketAuto.java @@ -13,6 +13,7 @@ import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierLine; import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathChain; import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Point; + @Autonomous(name = "Pre Loaded Blue Basket Auto", group = "Competition") public class PreLoadedBlueBasketAuto extends OpMode { private Telemetry telemetryA; @@ -118,5 +119,6 @@ public class PreLoadedBlueBasketAuto extends OpMode { public void loop() { follower.update(); follower.telemetryDebug(telemetryA); + } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/configs/RobotConstants.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/configs/RobotConstants.java index d68052e..36e2f16 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/configs/RobotConstants.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/configs/RobotConstants.java @@ -19,6 +19,8 @@ public class RobotConstants { public final static int liftToFloorPos = 350; public final static int liftToSubmarinePos = 350; public final static int liftToLowBucketPos = 2250; + public final static int liftToHighRung = 2250; + public final static int liftToHighBucketPos = 3850; public final static double liftPower = .625; } \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystem/LiftActionsSubsystem.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystem/LiftActionsSubsystem.java index 9cca186..03f91e5 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystem/LiftActionsSubsystem.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/subsystem/LiftActionsSubsystem.java @@ -21,7 +21,7 @@ public class LiftActionsSubsystem { public DcMotor lift; public enum LiftState { - FLOOR, LOW_BUCKET, HIGH_BUCKET, FLOAT, SUBMARINE + FLOOR, LOW_BUCKET, HIGH_BUCKET, FLOAT, SUBMARINE, } private LiftState liftState; @@ -58,6 +58,7 @@ public class LiftActionsSubsystem { public Action toLowBucketPosition() { return new MoveToPosition(liftToLowBucketPos, LiftState.LOW_BUCKET); + } public Action toHighBucketPosition() {