Skip to content

Commit

Permalink
Always throw RuntimeException
Browse files Browse the repository at this point in the history
The FTC SDK only catches `Exception` thrown by user code,
so switch all throwables to `RuntimeException`.
  • Loading branch information
rbrott committed Dec 21, 2023
1 parent e4cff73 commit ce080b0
Show file tree
Hide file tree
Showing 4 changed files with 10 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ public void runOpMode() throws InterruptedException {
telemetry.update();
}
} else {
throw new AssertionError();
throw new RuntimeException();
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,11 @@ public void runOpMode() throws InterruptedException {

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();
Expand All @@ -40,11 +40,11 @@ public void runOpMode() throws InterruptedException {

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();
Expand All @@ -57,7 +57,7 @@ public void runOpMode() throws InterruptedException {
.build());
}
} else {
throw new AssertionError();
throw new RuntimeException();
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ public void runOpMode() throws InterruptedException {
.splineTo(new Vector2d(60, 0), Math.PI)
.build());
} else {
throw new AssertionError();
throw new RuntimeException();
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ public static void register(OpModeManager manager) {
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(
Expand Down Expand Up @@ -123,7 +123,7 @@ public static void register(OpModeManager manager) {
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(
Expand All @@ -147,7 +147,7 @@ public static void register(OpModeManager manager) {
);
};
} else {
throw new AssertionError();
throw new RuntimeException();
}

manager.register(metaForClass(AngularRampLogger.class), new AngularRampLogger(dvf));
Expand Down

0 comments on commit ce080b0

Please sign in to comment.