Require odometry wheel positions to run ManualFeedbackTuner (#292)
This commit is contained in:
@ -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 final class ManualFeedbackTuner extends LinearOpMode {
|
||||
} 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()) {
|
||||
|
Reference in New Issue
Block a user