From 071e405f9236bf4502bc0025fb7f75d293dc8e4c Mon Sep 17 00:00:00 2001 From: j5155 <54331556+j5155@users.noreply.github.com> Date: Sun, 12 Nov 2023 20:55:25 -0900 Subject: [PATCH] Require odometry wheel positions to run ManualFeedbackTuner (#292) --- .../teamcode/tuning/ManualFeedbackTuner.java | 20 ++++++++++++++++++- 1 file changed, 19 insertions(+), 1 deletion(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/ManualFeedbackTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/ManualFeedbackTuner.java index 10466ccb7be6..469e6a4331b9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/ManualFeedbackTuner.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/ManualFeedbackTuner.java @@ -14,7 +14,16 @@ public final class ManualFeedbackTuner extends LinearOpMode { public void runOpMode() throws InterruptedException { if (TuningOpModes.DRIVE_CLASS.equals(MecanumDrive.class)) { MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0)); - + + if (drive.localizer instanceof TwoDeadWheelLocalizer) { + if (TwoDeadWheelLocalizer.PARAMS.perpXTicks == 0 && TwoDeadWheelLocalizer.PARAMS.parYTicks == 0) { + throw new AssertionError("Odometry wheel locations not set! Run AngularRampLogger to tune them."); + } + } else if (drive.localizer instanceof ThreeDeadWheelLocalizer) { + if (ThreeDeadWheelLocalizer.PARAMS.perpXTicks == 0 && ThreeDeadWheelLocalizer.PARAMS.par0YTicks == 0 && ThreeDeadWheelLocalizer.PARAMS.par1YTicks == 1) { + throw new AssertionError("Odometry wheel locations not set! Run AngularRampLogger to tune them."); + } + } waitForStart(); while (opModeIsActive()) { @@ -27,6 +36,15 @@ public void runOpMode() throws InterruptedException { } else if (TuningOpModes.DRIVE_CLASS.equals(TankDrive.class)) { TankDrive drive = new TankDrive(hardwareMap, new Pose2d(0, 0, 0)); + if (drive.localizer instanceof TwoDeadWheelLocalizer) { + if (TwoDeadWheelLocalizer.PARAMS.perpXTicks == 0 && TwoDeadWheelLocalizer.PARAMS.parYTicks == 0) { + throw new AssertionError("Odometry wheel locations not set! Run AngularRampLogger to tune them."); + } + } else if (drive.localizer instanceof ThreeDeadWheelLocalizer) { + if (ThreeDeadWheelLocalizer.PARAMS.perpXTicks == 0 && ThreeDeadWheelLocalizer.PARAMS.par0YTicks == 0 && ThreeDeadWheelLocalizer.PARAMS.par1YTicks == 1) { + throw new AssertionError("Odometry wheel locations not set! Run AngularRampLogger to tune them."); + } + } waitForStart(); while (opModeIsActive()) {