diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TwoDeadWheelLocalizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TwoDeadWheelLocalizer.java index e394377..d1e3208 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TwoDeadWheelLocalizer.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TwoDeadWheelLocalizer.java @@ -34,6 +34,8 @@ public final class TwoDeadWheelLocalizer implements Localizer { private final double inPerTick; + private double lastRawHeadingVel, headingVelOffset; + public TwoDeadWheelLocalizer(HardwareMap hardwareMap, IMU imu, double inPerTick) { par = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "par"))); perp = new OverflowEncoder(new RawEncoder(hardwareMap.get(DcMotorEx.class, "perp"))); @@ -48,6 +50,16 @@ public final class TwoDeadWheelLocalizer implements Localizer { FlightRecorder.write("TWO_DEAD_WHEEL_PARAMS", PARAMS); } + // see https://github.com/FIRST-Tech-Challenge/FtcRobotController/issues/617 + private double getHeadingVelocity() { + double rawHeadingVel = imu.getRobotAngularVelocity(AngleUnit.RADIANS).zRotationRate; + if (Math.abs(rawHeadingVel - lastRawHeadingVel) > Math.PI) { + headingVelOffset -= Math.signum(rawHeadingVel) * 2 * Math.PI; + } + lastRawHeadingVel = rawHeadingVel; + return headingVelOffset + rawHeadingVel; + } + public Twist2dDual