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 9f31b9e..f3073f6 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumDrive.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/MecanumDrive.java @@ -27,14 +27,14 @@ import com.acmerobotics.roadrunner.Twist2dDual; import com.acmerobotics.roadrunner.Twist2dIncrDual; import com.acmerobotics.roadrunner.Vector2d; import com.acmerobotics.roadrunner.VelConstraint; -import com.qualcomm.hardware.bosch.BNO055IMU; import com.qualcomm.hardware.lynx.LynxModule; +import com.qualcomm.hardware.rev.RevHubOrientationOnRobot; import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorEx; import com.qualcomm.robotcore.hardware.HardwareMap; +import com.qualcomm.robotcore.hardware.IMU; import com.qualcomm.robotcore.hardware.VoltageSensor; -import org.firstinspires.ftc.teamcode.util.BNO055Wrapper; import org.firstinspires.ftc.teamcode.util.Encoder; import org.firstinspires.ftc.teamcode.util.Localizer; import org.firstinspires.ftc.teamcode.util.LynxFirmwareVersion; @@ -95,7 +95,7 @@ public final class MecanumDrive { public final VoltageSensor voltageSensor; - public final BNO055Wrapper imu; + public final IMU imu; public final Localizer localizer; public Pose2d pose; @@ -176,11 +176,11 @@ public final class MecanumDrive { rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); - BNO055IMU baseImu = hardwareMap.get(BNO055IMU.class, "imu"); - BNO055IMU.Parameters parameters = new BNO055IMU.Parameters(); - parameters.angleUnit = BNO055IMU.AngleUnit.RADIANS; - baseImu.initialize(parameters); - imu = new BNO055Wrapper(baseImu); + imu = hardwareMap.get(IMU.class, "imu"); + IMU.Parameters parameters = new IMU.Parameters(new RevHubOrientationOnRobot( + RevHubOrientationOnRobot.LogoFacingDirection.UP, + RevHubOrientationOnRobot.UsbFacingDirection.FORWARD)); + imu.initialize(parameters); voltageSensor = hardwareMap.voltageSensor.iterator().next(); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TankDrive.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TankDrive.java index 34c8870..b5f00d1 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TankDrive.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TankDrive.java @@ -29,14 +29,14 @@ import com.acmerobotics.roadrunner.Twist2dIncrDual; import com.acmerobotics.roadrunner.Vector2d; import com.acmerobotics.roadrunner.Vector2dDual; import com.acmerobotics.roadrunner.VelConstraint; -import com.qualcomm.hardware.bosch.BNO055IMU; import com.qualcomm.hardware.lynx.LynxModule; +import com.qualcomm.hardware.rev.RevHubOrientationOnRobot; import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorEx; import com.qualcomm.robotcore.hardware.HardwareMap; +import com.qualcomm.robotcore.hardware.IMU; import com.qualcomm.robotcore.hardware.VoltageSensor; -import org.firstinspires.ftc.teamcode.util.BNO055Wrapper; import org.firstinspires.ftc.teamcode.util.Encoder; import org.firstinspires.ftc.teamcode.util.Localizer; import org.firstinspires.ftc.teamcode.util.LynxFirmwareVersion; @@ -93,7 +93,7 @@ public final class TankDrive { public final List leftMotors, rightMotors; - public final BNO055Wrapper imu; + public final IMU imu; public final VoltageSensor voltageSensor; @@ -191,11 +191,11 @@ public final class TankDrive { m.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); } - BNO055IMU baseImu = hardwareMap.get(BNO055IMU.class, "imu"); - BNO055IMU.Parameters parameters = new BNO055IMU.Parameters(); - parameters.angleUnit = BNO055IMU.AngleUnit.RADIANS; - baseImu.initialize(parameters); - imu = new BNO055Wrapper(baseImu); + imu = hardwareMap.get(IMU.class, "imu"); + IMU.Parameters parameters = new IMU.Parameters(new RevHubOrientationOnRobot( + RevHubOrientationOnRobot.LogoFacingDirection.UP, + RevHubOrientationOnRobot.UsbFacingDirection.FORWARD)); + imu.initialize(parameters); voltageSensor = hardwareMap.voltageSensor.iterator().next(); 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 50c0760..5c89659 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TwoDeadWheelLocalizer.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/TwoDeadWheelLocalizer.java @@ -8,8 +8,9 @@ import com.acmerobotics.roadrunner.Twist2dIncrDual; import com.acmerobotics.roadrunner.Vector2dDual; import com.qualcomm.robotcore.hardware.DcMotorEx; import com.qualcomm.robotcore.hardware.HardwareMap; +import com.qualcomm.robotcore.hardware.IMU; -import org.firstinspires.ftc.teamcode.util.BNO055Wrapper; +import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; import org.firstinspires.ftc.teamcode.util.Encoder; import org.firstinspires.ftc.teamcode.util.Localizer; import org.firstinspires.ftc.teamcode.util.RawEncoder; @@ -20,21 +21,21 @@ public final class TwoDeadWheelLocalizer implements Localizer { public static double PERP_X_TICKS = 0.0; public final Encoder par, perp; - public final BNO055Wrapper imu; + public final IMU imu; private int lastParPos, lastPerpPos; private Rotation2d lastHeading; private final double inPerTick; - public TwoDeadWheelLocalizer(HardwareMap hardwareMap, BNO055Wrapper imu, double inPerTick) { + public TwoDeadWheelLocalizer(HardwareMap hardwareMap, IMU imu, double inPerTick) { par = new RawEncoder(hardwareMap.get(DcMotorEx.class, "par")); perp = new RawEncoder(hardwareMap.get(DcMotorEx.class, "perp")); this.imu = imu; lastParPos = par.getPositionAndVelocity().position; lastPerpPos = perp.getPositionAndVelocity().position; - lastHeading = imu.getHeading(); + lastHeading = Rotation2d.exp(imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.RADIANS)); this.inPerTick = inPerTick; } @@ -42,13 +43,13 @@ public final class TwoDeadWheelLocalizer implements Localizer { public Twist2dIncrDual