From ce080b0b51d7913e58d4682e74b1c63653a74c68 Mon Sep 17 00:00:00 2001 From: Ryan Brott Date: Wed, 20 Dec 2023 18:10:52 -0800 Subject: [PATCH] Always throw `RuntimeException` The FTC SDK only catches `Exception` thrown by user code, so switch all throwables to `RuntimeException`. --- .../ftc/teamcode/tuning/LocalizationTest.java | 2 +- .../ftc/teamcode/tuning/ManualFeedbackTuner.java | 10 +++++----- .../firstinspires/ftc/teamcode/tuning/SplineTest.java | 2 +- .../ftc/teamcode/tuning/TuningOpModes.java | 6 +++--- 4 files changed, 10 insertions(+), 10 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/LocalizationTest.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/LocalizationTest.java index b75f768..ea7618d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/LocalizationTest.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/LocalizationTest.java @@ -55,7 +55,7 @@ public class LocalizationTest extends LinearOpMode { telemetry.update(); } } else { - throw new AssertionError(); + throw new RuntimeException(); } } } 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 b2206e9..0b6f193 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 @@ -19,11 +19,11 @@ public final class ManualFeedbackTuner extends LinearOpMode { 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."); + throw new RuntimeException("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."); + throw new RuntimeException("Odometry wheel locations not set! Run AngularRampLogger to tune them."); } } waitForStart(); @@ -40,11 +40,11 @@ public final class ManualFeedbackTuner extends LinearOpMode { 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."); + throw new RuntimeException("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."); + throw new RuntimeException("Odometry wheel locations not set! Run AngularRampLogger to tune them."); } } waitForStart(); @@ -57,7 +57,7 @@ public final class ManualFeedbackTuner extends LinearOpMode { .build()); } } else { - throw new AssertionError(); + throw new RuntimeException(); } } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/SplineTest.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/SplineTest.java index 7dc5822..21f6656 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/SplineTest.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/SplineTest.java @@ -32,7 +32,7 @@ public final class SplineTest extends LinearOpMode { .splineTo(new Vector2d(60, 0), Math.PI) .build()); } else { - throw new AssertionError(); + throw new RuntimeException(); } } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/TuningOpModes.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/TuningOpModes.java index 78ce476..3c79c20 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/TuningOpModes.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/TuningOpModes.java @@ -74,7 +74,7 @@ public final class TuningOpModes { parEncs.add(dl.par); perpEncs.add(dl.perp); } else { - throw new IllegalArgumentException("unknown localizer: " + md.localizer.getClass().getName()); + throw new RuntimeException("unknown localizer: " + md.localizer.getClass().getName()); } return new DriveView( @@ -123,7 +123,7 @@ public final class TuningOpModes { parEncs.add(dl.par); perpEncs.add(dl.perp); } else { - throw new IllegalArgumentException("unknown localizer: " + td.localizer.getClass().getName()); + throw new RuntimeException("unknown localizer: " + td.localizer.getClass().getName()); } return new DriveView( @@ -147,7 +147,7 @@ public final class TuningOpModes { ); }; } else { - throw new AssertionError(); + throw new RuntimeException(); } manager.register(metaForClass(AngularRampLogger.class), new AngularRampLogger(dvf));