Skip to content

Commit

Permalink
style: format code with Ktlint
Browse files Browse the repository at this point in the history
This commit fixes the style issues introduced in d16b0dc according to the output
from Ktlint.

Details: None
  • Loading branch information
deepsource-autofix[bot] authored and TheGamer1002 committed Oct 25, 2024
1 parent d16b0dc commit 3c95507
Showing 1 changed file with 3 additions and 4 deletions.
7 changes: 3 additions & 4 deletions src/main/java/frc/robot/RobotContainer.kt
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@ import edu.wpi.first.math.geometry.Pose2d
import edu.wpi.first.math.geometry.Rotation2d
import edu.wpi.first.math.geometry.Translation2d
import edu.wpi.first.wpilibj.DriverStation
import edu.wpi.first.wpilibj.RobotBase
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard
import edu.wpi.first.wpilibj2.command.Command
Expand All @@ -37,7 +36,7 @@ class RobotContainer {

private val controlChooser: SendableChooser<String> = SendableChooser()
private val controlChooserLogger: LoggedDashboardChooser<String>

private val speedChooser: SendableChooser<Double> = SendableChooser()
private val speedChooserLogger: LoggedDashboardChooser<Double>
private var MaxSpeed: Double = TunerConstants.kSpeedAt12VoltsMps // Initial max is true top speed
Expand Down Expand Up @@ -127,7 +126,7 @@ class RobotContainer {
val controlPick = Trigger { lastControl !== controlChooserLogger.get() }
controlPick.onTrue(Commands.runOnce({ newControlStyle() }))

val speedPick = Trigger { lastSpeed !== try { speedChooserLogger.get()!! } catch (e: Throwable) {0.65} }
val speedPick = Trigger { lastSpeed !== try { speedChooserLogger.get()!! } catch (e: Throwable) { 0.65 } }
speedPick.onTrue(Commands.runOnce({ newSpeed() }))

drv.x().and(drv.pov(0)).whileTrue(drivetrain.runDriveQuasiTest(SysIdRoutine.Direction.kForward))
Expand Down Expand Up @@ -184,7 +183,7 @@ class RobotContainer {
autoChooser.get()

private fun newControlStyle() {
lastControl = if(controlChooserLogger.get() != null) controlChooserLogger.get() else "2 Joysticks"
lastControl = if (controlChooserLogger.get() != null) controlChooserLogger.get() else "2 Joysticks"
when (controlChooserLogger.get()) {
"2 Joysticks" -> controlStyle = Supplier<SwerveRequest?> {
drive.withVelocityX(-drv.leftY * MaxSpeed) // Drive forward -Y
Expand Down

0 comments on commit 3c95507

Please sign in to comment.