Skip to content

Commit

Permalink
make ktlint happy
Browse files Browse the repository at this point in the history
  • Loading branch information
jpothen8 committed May 15, 2024
1 parent 3716f07 commit fa38602
Show file tree
Hide file tree
Showing 5 changed files with 11 additions and 22 deletions.
2 changes: 1 addition & 1 deletion src/main/kotlin/frc/team449/control/auto/PIDPoseAlign.kt
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ class PIDPoseAlign(
private val yController: PIDController = PIDController(AutoConstants.DEFAULT_Y_KP, 0.0, 0.0),
private val thetaController: PIDController = PIDController(AutoConstants.DEFAULT_ROTATION_KP, 0.0, 0.0),
poseTol: Pose2d = Pose2d(0.035, 0.035, Rotation2d(0.035)),
private val timeout: Double = 0.65,
private val timeout: Double = 0.65
) : Command() {

private val timer = Timer()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ open class SwerveModule(
turningMotor.set(
turnPid +
sign(desiredState.angle.radians - turningMotor.position) *
SwerveConstants.STEER_KS
SwerveConstants.STEER_KS
)
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,16 +44,6 @@ class FourPieceAmpHelper(
)
) - shot2Offset

init {
println(FieldConstants.BLUE_SPEAKER_POSE.getDistance(
Translation2d(
3.7641966342926025,
6.230502605438232
)
))
println(shot1PivotAngle)
}

override val routine =
ChoreoRoutine(
thetaController = PIDController(2.85, 0.0, 0.075),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -278,15 +278,15 @@ class ControllerBindings(
)
)
)
.andThen(
robot.pivot.moveAmp()
.alongWith(
robot.shooter.scoreAmp(),
WaitUntilCommand { robot.pivot.inAmpTolerance() && robot.shooter.atAmpSetpoint() }
.andThen(robot.feeder.intake())
)
.until { robot.infrared.get() && robot.closeToShooterInfrared.get() }
)
.andThen(
robot.pivot.moveAmp()
.alongWith(
robot.shooter.scoreAmp(),
WaitUntilCommand { robot.pivot.inAmpTolerance() && robot.shooter.atAmpSetpoint() }
.andThen(robot.feeder.intake())
)
.until { robot.infrared.get() && robot.closeToShooterInfrared.get() }
)
)

// driveController.leftBumper().onTrue(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -781,7 +781,6 @@ open class SpinShooter(
println(leftController.k.get(0, 0))
println(rightController.k.get(0, 0))


return if (RobotBase.isReal()) {
SpinShooter(
rightMotor,
Expand Down

0 comments on commit fa38602

Please sign in to comment.