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 6e834b7daf9b..9ed9df9386e4 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumDrive.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumDrive.java @@ -5,9 +5,7 @@ import com.acmerobotics.dashboard.canvas.Canvas; import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.telemetry.TelemetryPacket; -import com.acmerobotics.roadrunner.AccelConstraint; -import com.acmerobotics.roadrunner.Action; -import com.acmerobotics.roadrunner.Actions; +import com.acmerobotics.roadrunner.*; import com.acmerobotics.roadrunner.AngularVelConstraint; import com.acmerobotics.roadrunner.DualNum; import com.acmerobotics.roadrunner.HolonomicController; @@ -35,6 +33,7 @@ import com.qualcomm.robotcore.hardware.IMU; import com.qualcomm.robotcore.hardware.VoltageSensor; +import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; import org.firstinspires.ftc.teamcode.util.LogFiles; import org.firstinspires.ftc.teamcode.util.Encoder; import org.firstinspires.ftc.teamcode.util.Localizer; @@ -109,6 +108,7 @@ public class DriveLocalizer implements Localizer { public final Encoder leftFront, leftRear, rightRear, rightFront; private int lastLeftFrontPos, lastLeftRearPos, lastRightRearPos, lastRightFrontPos; + private Rotation2d lastHeading; public DriveLocalizer() { leftFront = new OverflowEncoder(new RawEncoder(MecanumDrive.this.leftFront)); @@ -120,6 +120,8 @@ public DriveLocalizer() { lastLeftRearPos = leftRear.getPositionAndVelocity().position; lastRightRearPos = rightRear.getPositionAndVelocity().position; lastRightFrontPos = rightFront.getPositionAndVelocity().position; + + lastHeading = Rotation2d.exp(imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.RADIANS)); } @Override @@ -129,31 +131,39 @@ public Twist2dIncrDual