Better spline test

This commit is contained in:
Ryan Brott
2023-12-24 13:30:20 -08:00
parent a890105110
commit a01ac85ef7

View File

@ -11,25 +11,26 @@ import org.firstinspires.ftc.teamcode.TankDrive;
public final class SplineTest extends LinearOpMode {
@Override
public void runOpMode() throws InterruptedException {
Pose2d beginPose = new Pose2d(0, 0, 0);
if (TuningOpModes.DRIVE_CLASS.equals(MecanumDrive.class)) {
MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
MecanumDrive drive = new MecanumDrive(hardwareMap, beginPose);
waitForStart();
Actions.runBlocking(
drive.actionBuilder(drive.pose)
drive.actionBuilder(beginPose)
.splineTo(new Vector2d(30, 30), Math.PI / 2)
.splineTo(new Vector2d(60, 0), Math.PI)
.splineTo(new Vector2d(0, 60), Math.PI)
.build());
} else if (TuningOpModes.DRIVE_CLASS.equals(TankDrive.class)) {
TankDrive drive = new TankDrive(hardwareMap, new Pose2d(0, 0, 0));
TankDrive drive = new TankDrive(hardwareMap, beginPose);
waitForStart();
Actions.runBlocking(
drive.actionBuilder(drive.pose)
drive.actionBuilder(beginPose)
.splineTo(new Vector2d(30, 30), Math.PI / 2)
.splineTo(new Vector2d(60, 0), Math.PI)
.splineTo(new Vector2d(0, 60), Math.PI)
.build());
} else {
throw new RuntimeException();