diff --git a/TeamCode/build.gradle b/TeamCode/build.gradle index ef612bc8cc90..13ecf4b651c4 100644 --- a/TeamCode/build.gradle +++ b/TeamCode/build.gradle @@ -27,13 +27,16 @@ repositories { maven { url = 'https://maven.brott.dev/' } + maven { + url = 'https://jitpack.io' + } } dependencies { implementation project(':FtcRobotController') - implementation "com.acmerobotics.roadrunner:ftc:0.1.13" - implementation "com.acmerobotics.roadrunner:core:1.0.0" - implementation "com.acmerobotics.roadrunner:actions:1.0.0" + implementation 'com.github.jdhs-ftc:road-runner-ftc-otos:master-SNAPSHOT' + implementation "com.acmerobotics.roadrunner:core:1.0.0-beta8" + implementation "com.acmerobotics.roadrunner:actions:1.0.0-beta8" implementation "com.acmerobotics.dashboard:dashboard:0.4.14" } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumDrive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumDrive.java index afdc28e19fb8..a0c6f4d6bc3f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumDrive.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumDrive.java @@ -126,7 +126,7 @@ public class DriveLocalizer implements Localizer { public final Encoder leftFront, leftBack, rightBack, rightFront; public final IMU imu; - private int lastLeftFrontPos, lastLeftBackPos, lastRightBackPos, lastRightFrontPos; + private double lastLeftFrontPos, lastLeftBackPos, lastRightBackPos, lastRightFrontPos; private Rotation2d lastHeading; private boolean initialized; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/ThreeDeadWheelLocalizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/ThreeDeadWheelLocalizer.java index d4aaf45231fc..cc24b138bb1e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/ThreeDeadWheelLocalizer.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/ThreeDeadWheelLocalizer.java @@ -31,7 +31,7 @@ public static class Params { public final double inPerTick; - private int lastPar0Pos, lastPar1Pos, lastPerpPos; + private double lastPar0Pos, lastPar1Pos, lastPerpPos; private boolean initialized; public ThreeDeadWheelLocalizer(HardwareMap hardwareMap, double inPerTick) { @@ -70,9 +70,9 @@ public Twist2dDual