Always throw RuntimeException
The FTC SDK only catches `Exception` thrown by user code, so switch all throwables to `RuntimeException`.
This commit is contained in:
@ -55,7 +55,7 @@ public class LocalizationTest extends LinearOpMode {
|
||||
telemetry.update();
|
||||
}
|
||||
} else {
|
||||
throw new AssertionError();
|
||||
throw new RuntimeException();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -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();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -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();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -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));
|
||||
|
Reference in New Issue
Block a user