Skip to content

Commit

Permalink
Require odometry wheel positions to run ManualFeedbackTuner (FIRST-Te…
Browse files Browse the repository at this point in the history
  • Loading branch information
j5155 authored Nov 13, 2023
1 parent e69e475 commit 071e405
Showing 1 changed file with 19 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -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()) {
Expand All @@ -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()) {
Expand Down

0 comments on commit 071e405

Please sign in to comment.