Rotate and Autos

This commit is contained in:
Shikhar
2026-01-19 13:42:16 -07:00
parent c68329c9ca
commit f600317435
14 changed files with 258 additions and 183 deletions
@@ -289,7 +289,8 @@ public class SwerveDrive extends SubsystemBase implements Queryable {
Translation2d fieldPosLead = robotSpeed.times(SwerveDriveConstants.AIM_LEAD_TIME.get()).plus(fieldPos);
// Calculate the angle between the current position and the lead position
Rotation2d ang = getPose2d().getTranslation().minus(fieldPosLead).getAngle();
Rotation2d ang = fieldPosLead.minus(getPose2d().getTranslation()).getAngle();
driveFieldAngle(leftStick, ang);
}