diff --git a/src/main/java/frc4388/robot/subsystems/SwerveDrive.java b/src/main/java/frc4388/robot/subsystems/SwerveDrive.java index a48a906..06a9cf1 100644 --- a/src/main/java/frc4388/robot/subsystems/SwerveDrive.java +++ b/src/main/java/frc4388/robot/subsystems/SwerveDrive.java @@ -54,9 +54,15 @@ public class SwerveDrive extends SubsystemBase { } public void oneModuleTest(SwerveModule module, Translation2d leftStick, Translation2d rightStick){ - double ang = (Math.atan2(rightStick.getY(), rightStick.getX()) / (Math.PI*2)); + // double ang = Math.atan2(rightStick.getY(), rightStick.getX()); + // rightStick.getAngle() + double speed = Math.sqrt(Math.pow(leftStick.getX(), 2) + Math.pow(leftStick.getY(), 2)); // System.out.println(ang); - module.go(ang); + // module.go(ang); + // Rotation2d rot = Rotation2d.fromRadians(ang); + Rotation2d rot = new Rotation2d(rightStick.getX(), rightStick.getY()); + SwerveModuleState state = new SwerveModuleState(speed, rot); + module.setDesiredState(state); } boolean stopped = false; diff --git a/src/main/java/frc4388/robot/subsystems/SwerveModule.java b/src/main/java/frc4388/robot/subsystems/SwerveModule.java index a8f7a6f..0bd2649 100644 --- a/src/main/java/frc4388/robot/subsystems/SwerveModule.java +++ b/src/main/java/frc4388/robot/subsystems/SwerveModule.java @@ -76,11 +76,11 @@ public class SwerveModule extends SubsystemBase { rotateToAngle(0); } - public void go(double ang){ - // double curang = this.encoder.getAbsolutePosition().getValue(); - System.out.println(getAngle().getDegrees()); - rotateToAngle(ang); - } + // public void go(double ang){ + // // double curang = this.encoder.getAbsolutePosition().getValue(); + // System.out.println(getAngle().getDegrees()); + // rotateToAngle(ang); + // } @Override public void periodic() { @@ -122,7 +122,7 @@ public class SwerveModule extends SubsystemBase { public Rotation2d getAngle() { // * Note: This assumes that the CANCoders are setup with the default feedback coefficient and the sensor value reports degrees. // return Rotation2d.fromDegrees(encoder.getAbsolutePosition()); - return Rotation2d.fromRotations(encoder.getAbsolutePosition().getValue()); + return Rotation2d.fromRotations(encoder.getPosition().getValue()); } public double getAngularVel() { @@ -163,6 +163,11 @@ public class SwerveModule extends SubsystemBase { ); } + // private SwerveModuleState optimizeState(SwerveModuleState desiredState) { + // Rotation2d curRot = this.getAngle(); + + // } + /** * Returns the current position of the SwerveModule * @return The current position of the SwerveModule in meters traveled by the driveMotor and the angle of the angleMotor. @@ -176,12 +181,17 @@ public class SwerveModule extends SubsystemBase { * @param desiredState a SwerveModuleState representing the desired new state of the module // */ public void setDesiredState(SwerveModuleState desiredState) { - SwerveModuleState state = SwerveModuleState.optimize(desiredState, this.getAngle()); + Rotation2d currentRotation = this.getAngle(); + + SwerveModuleState state = SwerveModuleState.optimize(desiredState, currentRotation); + + // calculate the difference between our current rotational position and our new rotational position + Rotation2d rotationDelta = state.angle.minus(currentRotation); - Rotation2d rot = state.angle; double speed = Units.metersToFeet(state.speedMetersPerSecond) / SwerveDriveConstants.MAX_SPEED_FEET_PER_SECOND; - rotateToAngle(rot.getRotations()); + rotateToAngle(rotationDelta.getRotations() + currentRotation.getRotations()); + driveMotor.set(Math.max(Math.min(speed, 1.), -1.)); }