Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fixed turn to angle #57

Merged
merged 2 commits into from
Feb 10, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 5 additions & 4 deletions src/main/java/frc/subsystem/Superstructure.java
Original file line number Diff line number Diff line change
@@ -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;
Expand Down Expand Up @@ -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
}
},
Expand Down Expand Up @@ -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);
Expand Down Expand Up @@ -231,7 +232,7 @@ public static Superstructure getSuperstructure() {
return superstructure;
}

public double getTargetAngleRad() {
return targetAngleRad;
public Rotation2d getTargetAngle() {
return targetAngle;
}
}
29 changes: 19 additions & 10 deletions src/main/java/frc/subsystem/drive/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down Expand Up @@ -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) {
Expand Down
Loading