Skip to content

Commit

Permalink
🎨 Spotless :/
Browse files Browse the repository at this point in the history
  • Loading branch information
chaoticthegreat committed Aug 30, 2024
1 parent b0a7fdd commit 0d210b0
Showing 1 changed file with 14 additions and 9 deletions.
23 changes: 14 additions & 9 deletions src/main/java/frc/robot/subsystems/turret/Turret.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.PIDCommand;
import frc.robot.subsystems.swerve.CommandSwerveDrivetrain;
Expand Down Expand Up @@ -53,8 +52,10 @@ public void periodic() {
}

/**
* @see <a href="https://docs.google.com/spreadsheets/d/1WOmYiwrWg-2iJdFzRZITXqLrtTegc7WbxJ2SQzn8VHs/edit?gid=0#gid=0">Chinese remainder theorem sheet calculator</a>
* Uses the calculations from the sheet to calculate the turret position from two encoders
* @see <a
* href="https://docs.google.com/spreadsheets/d/1WOmYiwrWg-2iJdFzRZITXqLrtTegc7WbxJ2SQzn8VHs/edit?gid=0#gid=0">Chinese
* remainder theorem sheet calculator</a> Uses the calculations from the sheet to calculate
* the turret position from two encoders
* @param cancoder1
* @param cancoder2
* @return rotation2d of the turret position
Expand All @@ -80,8 +81,10 @@ public static Rotation2d getTurretPosition(Rotation2d cancoder1, Rotation2d canc
*/
public Command setPositionRelativeToSwerve(Rotation2d position, CommandSwerveDrivetrain swerve) {
return this.run(
() ->turretIO.setPosition(position.minus(swerve.getState().Pose.getRotation()).getRotations() / TurretConstants.gearRatio));

() ->
turretIO.setPosition(
position.minus(swerve.getState().Pose.getRotation()).getRotations()
/ TurretConstants.gearRatio));
}

/**
Expand All @@ -90,8 +93,7 @@ public Command setPositionRelativeToSwerve(Rotation2d position, CommandSwerveDri
*/
public Command setPosition(Rotation2d position) {
return this.runOnce(
() ->
turretIO.setPosition(position.getRotations()/ TurretConstants.gearRatio));
() -> turretIO.setPosition(position.getRotations() / TurretConstants.gearRatio));
}

/**
Expand All @@ -102,7 +104,9 @@ public Command zero() {
}

/**
* Will run a PID loop that tracks the tx of the speaker tag and attempts to get it to 0 by moving the turret so the LL crosshair is centered
* Will run a PID loop that tracks the tx of the speaker tag and attempts to get it to 0 by moving
* the turret so the LL crosshair is centered
*
* @param vision Reference to the vision subsystem
* @return Command to run a PID loop to lock the turret to the speaker tag
*/
Expand Down Expand Up @@ -141,7 +145,8 @@ public Command lockToSpeakerPose(CommandSwerveDrivetrain swerve, Pose2d speakerP
}

/**
* @return Command to reset the turret to the forward limit if it is past the forward limit, or to the reverse limit if it is past the reverse limit
* @return Command to reset the turret to the forward limit if it is past the forward limit, or to
* the reverse limit if it is past the reverse limit
*/
public Command reset() {
return this.runOnce(
Expand Down

0 comments on commit 0d210b0

Please sign in to comment.