diff --git a/src/main/java/frc/subsystem/Superstructure.java b/src/main/java/frc/subsystem/Superstructure.java index 10b58fc..2225d24 100644 --- a/src/main/java/frc/subsystem/Superstructure.java +++ b/src/main/java/frc/subsystem/Superstructure.java @@ -1,5 +1,6 @@ package frc.subsystem; +import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj.DriverStation; import frc.robot.Constants; import frc.robot.Robot; @@ -124,7 +125,7 @@ public void update() { superstructure.setWantedShooterPosition(0); superstructure.setCurrentState(States.GENERAL_INTERMEDIATE); } - superstructure.targetAngleRad = 0; // get the target angle needed to aim at speaker + superstructure.targetAngle = drive.findAngleToSpeaker(); // get the target angle needed to aim at speaker // set target angle and wrist position based on other logic to determine front or back } }, @@ -199,7 +200,7 @@ public void setCurrentState(States newState) { } private double wantedShooterPosition; - private double targetAngleRad; + private Rotation2d targetAngle; public void update() { currentState.update(); arm.setPosition(currentState.armPos); @@ -231,7 +232,7 @@ public static Superstructure getSuperstructure() { return superstructure; } - public double getTargetAngleRad() { - return targetAngleRad; + public Rotation2d getTargetAngle() { + return targetAngle; } } \ No newline at end of file diff --git a/src/main/java/frc/subsystem/drive/Drive.java b/src/main/java/frc/subsystem/drive/Drive.java index 1e36fc2..cfb2b9b 100644 --- a/src/main/java/frc/subsystem/drive/Drive.java +++ b/src/main/java/frc/subsystem/drive/Drive.java @@ -264,8 +264,8 @@ public synchronized void swerveDriveFieldRelative(@NotNull ControllerDriveInputs kinematicLimit = KinematicLimits.NORMAL_DRIVING.kinematicLimit; } - public void swerveDriveTargetAngle(@NotNull ControllerDriveInputs inputs, double targetAngleRad) { - double turn = turnPID.calculate(gyroInputs.rotation2d.getRadians(), targetAngleRad); + public void swerveDriveTargetAngle(@NotNull ControllerDriveInputs inputs, Rotation2d targetAngleRad) { + double turn = turnPID.calculate(gyroInputs.rotation2d.getRadians(), targetAngleRad.getRadians()); nextChassisSpeeds = ChassisSpeeds.fromFieldRelativeSpeeds(DRIVE_HIGH_SPEED_M * inputs.getX(), DRIVE_HIGH_SPEED_M * inputs.getY(), turn * MAX_TELEOP_TURN_SPEED, @@ -309,21 +309,30 @@ public double findDistanceToSpeaker() { * @return angle of robot needed to face speaker */ @AutoLogOutput(key = "Drive/Angle to Speaker") - public double findAngleToSpeaker() { - - double yDistanceToBlue = blueAllianceSpeaker.getY() - poseEstimator.getEstimatedPosition().getY(); - double yDistanceToRed = redAllianceSpeaker.getY() - poseEstimator.getEstimatedPosition().getY(); + public Rotation2d findAngleToSpeaker() { + Rotation2d heading = gyroInputs.rotation2d; + double deltaX; + double deltaY; + Rotation2d delta; if (ally.isPresent()) { if (ally.get() == DriverStation.Alliance.Red) { - return Math.atan2(yDistanceToRed, (redAllianceSpeaker.getX() - poseEstimator.getEstimatedPosition().getX())); + deltaY = redAllianceSpeaker.getY() - getPose().getY(); + deltaX = redAllianceSpeaker.getX() - getPose().getX(); + } else { + deltaY = blueAllianceSpeaker.getY() - getPose().getY(); + deltaX = blueAllianceSpeaker.getX() - getPose().getX(); } - if (ally.get() == DriverStation.Alliance.Blue) { - return Math.atan2(yDistanceToBlue, (blueAllianceSpeaker.getX() - poseEstimator.getEstimatedPosition().getX())); + Rotation2d target = new Rotation2d(deltaX, deltaY); + delta = target.minus(heading); + + if(Math.abs(delta.getRadians()) > (Math.PI / 2)) { + target.rotateBy(Rotation2d.fromRadians(Math.PI)); } + return target; } - return 0; + return null; } public void resetOdometry(Pose2d pose) {