From 4fc5d6465b08e583a0f36015afe663d1fb5eca8d Mon Sep 17 00:00:00 2001 From: Ryan Brott Date: Mon, 2 Jan 2023 16:59:15 -0800 Subject: [PATCH] Bump RR --- TeamCode/build.gradle | 3 ++- .../ftc/teamcode/tuning/ManualFeedbackTuner.java | 8 ++++---- 2 files changed, 6 insertions(+), 5 deletions(-) diff --git a/TeamCode/build.gradle b/TeamCode/build.gradle index 80e1045..e15cd62 100644 --- a/TeamCode/build.gradle +++ b/TeamCode/build.gradle @@ -34,7 +34,8 @@ dependencies { annotationProcessor files('lib/OpModeAnnotationProcessor.jar') implementation 'com.acmerobotics.dashboard:dashboard:0.4.7' - implementation 'com.acmerobotics.roadrunner:core:1.0.0-beta0' + implementation 'com.acmerobotics.roadrunner:core:1.0.0-beta1' + implementation 'com.acmerobotics.roadrunner:actions:1.0.0-beta1' implementation 'com.fasterxml.jackson.core:jackson-databind:2.12.7' } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/ManualFeedbackTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/ManualFeedbackTuner.java index 036e2db..9e6746d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/ManualFeedbackTuner.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tuning/ManualFeedbackTuner.java @@ -19,8 +19,8 @@ public final class ManualFeedbackTuner extends ActionOpMode { while (opModeIsActive()) { runBlocking( drive.actionBuilder(drive.pose) - .forward(DISTANCE) - .forward(-DISTANCE) + .lineToX(DISTANCE) + .lineToX(0) .build()); } } else if (TuningOpModes.DRIVE_CLASS.equals(TankDrive.class)) { @@ -31,8 +31,8 @@ public final class ManualFeedbackTuner extends ActionOpMode { while (opModeIsActive()) { runBlocking( drive.actionBuilder(drive.pose) - .forward(DISTANCE) - .forward(-DISTANCE) + .lineToX(DISTANCE) + .lineToX(0) .build()); } } else {