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 f5778d3 according to the output
from Ktlint.

Details: #8
  • Loading branch information
deepsource-autofix[bot] authored Oct 25, 2024
1 parent f5778d3 commit e1f5e27
Show file tree
Hide file tree
Showing 7 changed files with 163 additions and 148 deletions.
28 changes: 14 additions & 14 deletions src/main/java/frc/robot/Robot.kt
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ import org.littletonrobotics.junction.wpilog.WPILOGWriter
class Robot : LoggedRobot() {
private var robotContainer: RobotContainer = RobotContainer()
private var autonomousCommand: Command? = null

override fun robotInit() {
Logger.recordMetadata("ProjectName", "FRC2024-offseason")
// Log to a USB stick ("/U/logs")
Expand All @@ -30,52 +30,52 @@ class Robot : LoggedRobot() {
// Enables power distribution logging
PowerDistribution(
1,
PowerDistribution.ModuleType.kRev
PowerDistribution.ModuleType.kRev,
)

// Start logging! No more data receivers, replay sources, or metadata values may be added.
Logger.start()
SignalLogger.start()

DriverStation.silenceJoystickConnectionWarning(true)
robotContainer.drivetrain.daqThread.setThreadPriority(99)

Check warning

Code scanning / detekt

Report magic numbers. Magic number is a numeric literal that is not defined as a constant and hence it's unclear what the purpose of this number is. It's better to declare such numbers as constants and give them a proper name. By default, -1, 0, 1, and 2 are not considered to be magic numbers. Warning

This expression contains a magic number. Consider defining it to a well named constant.

Pathfinding.setPathfinder(LocalADStarAK())
PathfindingCommand.warmupCommand().schedule()
}

override fun robotPeriodic() {
CommandScheduler.getInstance().run()
}

override fun disabledInit() {}
override fun disabledPeriodic() {}
override fun disabledExit() {}

override fun autonomousInit() {
autonomousCommand = robotContainer.autoCommand

if (autonomousCommand != null) {
autonomousCommand?.schedule()
}
}

override fun autonomousPeriodic() {}
override fun autonomousExit() {}

override fun teleopInit() {
if (autonomousCommand != null) {
autonomousCommand!!.cancel()
}
}

override fun teleopPeriodic() {}
override fun teleopExit() {}

override fun testInit() {
CommandScheduler.getInstance().cancelAll()
}

override fun testPeriodic() {}
override fun testExit() {}
override fun simulationPeriodic() {}
Expand Down
102 changes: 55 additions & 47 deletions src/main/java/frc/robot/RobotContainer.kt
Original file line number Diff line number Diff line change
Expand Up @@ -33,27 +33,32 @@ import kotlin.math.sin
class RobotContainer {
/** Defaults to true top speed. */
private var maxSpeed: Double = TunerConstants.kSpeedAt12VoltsMps

/** Reduction in speed from Max Speed, 0.1 = 10% */
private val turtleSpeed = 0.1

Check warning

Code scanning / detekt

Report magic numbers. Magic number is a numeric literal that is not defined as a constant and hence it's unclear what the purpose of this number is. It's better to declare such numbers as constants and give them a proper name. By default, -1, 0, 1, and 2 are not considered to be magic numbers. Warning

This expression contains a magic number. Consider defining it to a well named constant.

/**
* .75 rotation per second max angular velocity. Adjust for max
* turning rate speed.
*/
private val maxAngularRate = Math.PI * 1.5

Check warning

Code scanning / detekt

Report magic numbers. Magic number is a numeric literal that is not defined as a constant and hence it's unclear what the purpose of this number is. It's better to declare such numbers as constants and give them a proper name. By default, -1, 0, 1, and 2 are not considered to be magic numbers. Warning

This expression contains a magic number. Consider defining it to a well named constant.

/**
* .75 rotation per second max angular velocity. Adjust for max
* turning rate speed.
*/
private val turtleAngularRate = Math.PI * 0.5

Check warning

Code scanning / detekt

Report magic numbers. Magic number is a numeric literal that is not defined as a constant and hence it's unclear what the purpose of this number is. It's better to declare such numbers as constants and give them a proper name. By default, -1, 0, 1, and 2 are not considered to be magic numbers. Warning

This expression contains a magic number. Consider defining it to a well named constant.

/** This will be updated when turtle and reset to MaxAngularRate */
private var angularRate = maxAngularRate
// Bindings for necessary control of the swerve drive platform
/** Driver xbox controller. */
private var drv: CommandXboxController = CommandXboxController(0)

/** Operator xbox controller. */
private var op: CommandXboxController = CommandXboxController(1)
var drivetrain: CommandSwerveDrivetrain = TunerConstants.DriveTrain

/**
* Field-centric driving in Open Loop, can change to closed
* loop after characterization.
Expand All @@ -72,32 +77,32 @@ class RobotContainer {
private var controlStyle: Supplier<SwerveRequest?>? = null
private var lastControl = "2 Joysticks"
private var lastSpeed = 0.65

Check warning

Code scanning / detekt

Report magic numbers. Magic number is a numeric literal that is not defined as a constant and hence it's unclear what the purpose of this number is. It's better to declare such numbers as constants and give them a proper name. By default, -1, 0, 1, and 2 are not considered to be magic numbers. Warning

This expression contains a magic number. Consider defining it to a well named constant.

private val armSubsystem: ArmSubsystem = ArmSubsystem
private val visionSubsystem: VisionSubsystem = VisionSubsystem(drivetrain)
var vision: VisionSubsystem = VisionSubsystem(drivetrain)

// dashboard options

private val autoChooser: LoggedDashboardChooser<Command>
private val controlChooser: SendableChooser<String> = SendableChooser()
private val controlChooserLogger: LoggedDashboardChooser<String>
private val speedChooser: SendableChooser<Double> = SendableChooser()
private val speedChooserLogger: LoggedDashboardChooser<Double>

val autoCommand: Command?
get() = // First put the drivetrain into auto run mode, then run the auto
autoChooser.get()

private fun configureBindings() {
SmartDashboard.putData("Auto Chooser", autoChooser.sendableChooser)

newControlStyle()
newSpeed()

armSubsystem.defaultCommand =
armSubsystem.getCommand { op.rightTriggerAxis - op.leftTriggerAxis }

drv.a().whileTrue(drivetrain.applyRequest { brake })
drv.b()
.whileTrue(
Expand Down Expand Up @@ -125,15 +130,15 @@ class RobotContainer {
Commands.runOnce({
maxSpeed =
TunerConstants.kSpeedAt12VoltsMps *
speedChooserLogger.get()
speedChooserLogger.get()
})
.andThen({ angularRate = maxAngularRate }),
)

if (Utils.isSimulation()) {
drivetrain.seedFieldRelative(Pose2d(Translation2d(), Rotation2d.fromDegrees(0.0)))
}

drivetrain.registerTelemetry { state: SwerveDrivetrain.SwerveDriveState ->
logger.telemeterize(state)
}
Expand All @@ -148,50 +153,50 @@ class RobotContainer {
}
}
speedPick.onTrue(Commands.runOnce({ newSpeed() }))

drv.x()
.and(drv.pov(0))
.whileTrue(drivetrain.runDriveQuasiTest(SysIdRoutine.Direction.kForward))
drv.x()
.and(drv.pov(180))

Check warning

Code scanning / detekt

Report magic numbers. Magic number is a numeric literal that is not defined as a constant and hence it's unclear what the purpose of this number is. It's better to declare such numbers as constants and give them a proper name. By default, -1, 0, 1, and 2 are not considered to be magic numbers. Warning

This expression contains a magic number. Consider defining it to a well named constant.
.whileTrue(drivetrain.runDriveQuasiTest(SysIdRoutine.Direction.kReverse))

drv.y()
.and(drv.pov(0))
.whileTrue(drivetrain.runDriveDynamTest(SysIdRoutine.Direction.kForward))
drv.y()
.and(drv.pov(180))

Check warning

Code scanning / detekt

Report magic numbers. Magic number is a numeric literal that is not defined as a constant and hence it's unclear what the purpose of this number is. It's better to declare such numbers as constants and give them a proper name. By default, -1, 0, 1, and 2 are not considered to be magic numbers. Warning

This expression contains a magic number. Consider defining it to a well named constant.
.whileTrue(drivetrain.runDriveDynamTest(SysIdRoutine.Direction.kReverse))

drv.a()
.and(drv.pov(0))
.whileTrue(drivetrain.runSteerQuasiTest(SysIdRoutine.Direction.kForward))
drv.a()
.and(drv.pov(180))

Check warning

Code scanning / detekt

Report magic numbers. Magic number is a numeric literal that is not defined as a constant and hence it's unclear what the purpose of this number is. It's better to declare such numbers as constants and give them a proper name. By default, -1, 0, 1, and 2 are not considered to be magic numbers. Warning

This expression contains a magic number. Consider defining it to a well named constant.
.whileTrue(drivetrain.runSteerQuasiTest(SysIdRoutine.Direction.kReverse))

drv.b()
.and(drv.pov(0))
.whileTrue(drivetrain.runSteerDynamTest(SysIdRoutine.Direction.kForward))
drv.b()
.and(drv.pov(180))

Check warning

Code scanning / detekt

Report magic numbers. Magic number is a numeric literal that is not defined as a constant and hence it's unclear what the purpose of this number is. It's better to declare such numbers as constants and give them a proper name. By default, -1, 0, 1, and 2 are not considered to be magic numbers. Warning

This expression contains a magic number. Consider defining it to a well named constant.
.whileTrue(drivetrain.runSteerDynamTest(SysIdRoutine.Direction.kReverse))

// Drivetrain needs to be placed against a sturdy wall and test stopped immediately upon
// wheel slip
drv.back().and(drv.pov(0)).whileTrue(drivetrain.runDriveSlipTest())
drv.rightBumper().whileTrue(drivetrain.rotateToAngleDiff(visionSubsystem.getNoteCamAngle()))

// TODO make sure this works and probably also see if we can't get it to also move the robot forward a bit to center it w/ the arm

Check warning

Code scanning / detekt

Line detected that is longer than the defined maximum line length in the code style. Warning

Line detected that is longer than the defined maximum line length in the code style.
}

init {
// Detect if controllers are missing / stop multiple warnings
DriverStation.silenceJoystickConnectionWarning(true)

// Build an auto chooser. This will use Commands.none() as the default option.
autoChooser = LoggedDashboardChooser("Auto Chooser", AutoBuilder.buildAutoChooser())

controlChooser.addOption("1 Joystick Rotation Triggers", "1 Joystick Rotation Triggers")
controlChooser.addOption(
"Split Joysticks Rotation Triggers",
Expand All @@ -200,7 +205,7 @@ class RobotContainer {
controlChooser.addOption("2 Joysticks with Gas Pedal", "2 Joysticks with Gas Pedal")
controlChooser.setDefaultOption("2 Joysticks", "2 Joysticks")
controlChooserLogger = LoggedDashboardChooser("Control Chooser", controlChooser)

speedChooser.addOption("100%", 1.0)
speedChooser.addOption("95%", 0.95)
speedChooser.addOption("90%", 0.9)
Expand All @@ -214,15 +219,18 @@ class RobotContainer {
speedChooser.addOption("50%", 0.5)
speedChooser.addOption("35%", 0.35)
speedChooserLogger = LoggedDashboardChooser("Speed Chooser", speedChooser)

configureBindings()
}

private fun newControlStyle() {
lastControl =
if (controlChooserLogger.get() != null) controlChooserLogger.get()
else "2 Joysticks"

if (controlChooserLogger.get() != null) {
controlChooserLogger.get()
} else {
"2 Joysticks"
}

when (controlChooserLogger.get()) {
"2 Joysticks" ->
controlStyle =
Expand All @@ -231,75 +239,75 @@ class RobotContainer {
drive.withVelocityX(-drv.leftY * maxSpeed)
// Drive left with negative X (left)
.withVelocityY(
-drv.leftX * maxSpeed
-drv.leftX * maxSpeed,
)
// Drive counterclockwise with negative X (left)
.withRotationalRate(-drv.rightX * angularRate)
}

"1 Joystick Rotation Triggers" ->
controlStyle =
Supplier<SwerveRequest?> {
// Drive forward -Y
drive.withVelocityX(-drv.leftY * maxSpeed)
// Drive left with negative X (left)
.withVelocityY(
-drv.leftX * maxSpeed
-drv.leftX * maxSpeed,
)
.withRotationalRate(
(drv.leftTriggerAxis - drv.rightTriggerAxis) *
angularRate
angularRate,
)
}

"Split Joysticks Rotation Triggers" ->
controlStyle =
Supplier<SwerveRequest?> {
// Left stick forward/back
drive.withVelocityX(
-drv.leftY * maxSpeed
-drv.leftY * maxSpeed,
)
// Right stick strafe
.withVelocityY(-drv.rightX * maxSpeed)
.withRotationalRate(
(drv.leftTriggerAxis - drv.rightTriggerAxis) *
angularRate
angularRate,
)
}

"2 Joysticks with Gas Pedal" ->
controlStyle =
Supplier<SwerveRequest?> {
val stickX: Double = -drv.leftX
val stickY: Double = -drv.leftY
val angle: Double = atan2(stickX, stickY)

// left x * gas
drive.withVelocityX(
cos(angle) * drv.rightTriggerAxis * maxSpeed
cos(angle) * drv.rightTriggerAxis * maxSpeed,
)
// Angle of left stick Y * gas pedal
.withVelocityY(
sin(angle) * drv.rightTriggerAxis * maxSpeed
sin(angle) * drv.rightTriggerAxis * maxSpeed,
)
// Drive counterclockwise with negative X (left)
.withRotationalRate(
-drv.rightX * angularRate
-drv.rightX * angularRate,
)
}

else -> {
DriverStation.reportWarning(
"RC: Invalid control style: " + controlChooserLogger.get(),
false
false,
)
controlStyle =
Supplier<SwerveRequest?> {
// Drive forward -Y
drive.withVelocityX(-drv.leftY * maxSpeed)
// Drive left with negative X (left)
.withVelocityY(
-drv.leftX * maxSpeed
-drv.leftX * maxSpeed,
)
.withRotationalRate(-drv.rightX * angularRate)
}
Expand All @@ -310,30 +318,30 @@ class RobotContainer {
} catch (_: Exception) {
DriverStation.reportWarning(
"RC: Failed to cancel default command? Maybe something else...",
true
true,
)

controlStyle =
Supplier<SwerveRequest?> {
// Drive forward -Y
drive.withVelocityX(-drv.leftY * maxSpeed)
// Drive left with negative X (left)
.withVelocityY(
-drv.leftX * maxSpeed
-drv.leftX * maxSpeed,
)
.withRotationalRate(-drv.rightX * angularRate)
}
}
drivetrain.defaultCommand = drivetrain.applyRequest(controlStyle!!).ignoringDisable(true)
}

private fun newSpeed() {
lastSpeed = try {
speedChooserLogger.get()
} catch (_: Exception) {
DriverStation.reportWarning(
"RC: Failed to get speed, value is: " + speedChooserLogger.get(),
false
false,
)
0.65

Check warning

Code scanning / detekt

Report magic numbers. Magic number is a numeric literal that is not defined as a constant and hence it's unclear what the purpose of this number is. It's better to declare such numbers as constants and give them a proper name. By default, -1, 0, 1, and 2 are not considered to be magic numbers. Warning

This expression contains a magic number. Consider defining it to a well named constant.
}
Expand Down
Loading

0 comments on commit e1f5e27

Please sign in to comment.