From d03ec5ca79c9e5f82a15a2575972608a1eab34f7 Mon Sep 17 00:00:00 2001 From: "deepsource-autofix[bot]" <62050782+deepsource-autofix[bot]@users.noreply.github.com> Date: Sat, 2 Nov 2024 13:24:22 +0000 Subject: [PATCH] style: format code with Ktlint This commit fixes the style issues introduced in a213620 according to the output from Ktlint. Details: None --- .../drive/CommandSwerveDrivetrain.kt | 110 ++++++++++-------- 1 file changed, 61 insertions(+), 49 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/drive/CommandSwerveDrivetrain.kt b/src/main/java/frc/robot/subsystems/drive/CommandSwerveDrivetrain.kt index 45f3970..8224df6 100755 --- a/src/main/java/frc/robot/subsystems/drive/CommandSwerveDrivetrain.kt +++ b/src/main/java/frc/robot/subsystems/drive/CommandSwerveDrivetrain.kt @@ -15,12 +15,10 @@ import com.pathplanner.lib.util.DriveFeedforwards import edu.wpi.first.math.Matrix import edu.wpi.first.math.VecBuilder 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.geometry.Translation2d import edu.wpi.first.math.geometry.Translation3d import edu.wpi.first.math.kinematics.ChassisSpeeds -import edu.wpi.first.math.kinematics.SwerveDriveOdometry import edu.wpi.first.math.numbers.N1 import edu.wpi.first.math.numbers.N3 import edu.wpi.first.units.Units @@ -34,8 +32,8 @@ import edu.wpi.first.wpilibj2.command.Command import edu.wpi.first.wpilibj2.command.Subsystem import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Mechanism -import frc.robot.util.RectanglePoseArea import frc.robot.subsystems.vision.VisionSubsystem +import frc.robot.util.RectanglePoseArea import java.util.function.DoubleSupplier import java.util.function.Supplier import kotlin.math.PI @@ -50,7 +48,6 @@ class CommandSwerveDrivetrain : SwerveDrivetrain, Subsystem { private var thetaController: PIDController = PIDController(1.1, 0.0, 0.125) // TODO tune this - /* Keep track if we've ever applied the operator perspective before or not */ private var m_hasAppliedOperatorPerspective = false @@ -65,28 +62,33 @@ class CommandSwerveDrivetrain : SwerveDrivetrain, Subsystem { /* SysId routine for characterizing translation. This is used to find PID gains for the drive motors. */ private val m_sysIdRoutineTranslation = SysIdRoutine( SysIdRoutine.Config( - null, // Use default ramp rate (1 V/s) - Units.Volts.of(4.0), // Reduce dynamic step voltage to 4 V to prevent brownout - null - ) // Use default timeout (10 s) - // Log state with SignalLogger class - { state: SysIdRoutineLog.State -> SignalLogger.writeString("SysIdTranslation_State", state.toString()) }, + null, // Use default ramp rate (1 V/s) + Units.Volts.of(4.0), // Reduce dynamic step voltage to 4 V to prevent brownout + null, + ) // Use default timeout (10 s) + // Log state with SignalLogger class + { state: SysIdRoutineLog.State -> SignalLogger.writeString("SysIdTranslation_State", state.toString()) }, Mechanism( - { output: Voltage? -> setControl(m_translationCharacterization.withVolts(output)) }, null, this - ) + { output: Voltage? -> setControl(m_translationCharacterization.withVolts(output)) }, + null, + this, + ), ) /* SysId routine for characterizing steer. This is used to find PID gains for the steer motors. */ private val m_sysIdRoutineSteer = SysIdRoutine( SysIdRoutine.Config( - null, // Use default ramp rate (1 V/s) - Units.Volts.of(7.0), // Use dynamic voltage of 7 V - null - ) // Use default timeout (10 s) - // Log state with SignalLogger class - { state: SysIdRoutineLog.State -> SignalLogger.writeString("SysIdSteer_State", state.toString()) }, Mechanism( - { volts: Voltage? -> setControl(m_steerCharacterization.withVolts(volts)) }, null, this - ) + null, // Use default ramp rate (1 V/s) + Units.Volts.of(7.0), // Use dynamic voltage of 7 V + null, + ) // Use default timeout (10 s) + // Log state with SignalLogger class + { state: SysIdRoutineLog.State -> SignalLogger.writeString("SysIdSteer_State", state.toString()) }, + Mechanism( + { volts: Voltage? -> setControl(m_steerCharacterization.withVolts(volts)) }, + null, + this, + ), ) /* @@ -97,18 +99,21 @@ class CommandSwerveDrivetrain : SwerveDrivetrain, Subsystem { private val m_sysIdRoutineRotation = SysIdRoutine( SysIdRoutine.Config( /* This is in radians per secondĀ², but SysId only supports "volts per second" */ Units.Volts.of(Math.PI / 6) - .per(Units.Second), /* This is in radians per second, but SysId only supports "volts" */ - Units.Volts.of(Math.PI), null - ) // Use default timeout (10 s) - // Log state with SignalLogger class - { state: SysIdRoutineLog.State -> SignalLogger.writeString("SysIdRotation_State", state.toString()) }, + .per(Units.Second), /* This is in radians per second, but SysId only supports "volts" */ + Units.Volts.of(Math.PI), + null, + ) // Use default timeout (10 s) + // Log state with SignalLogger class + { state: SysIdRoutineLog.State -> SignalLogger.writeString("SysIdRotation_State", state.toString()) }, Mechanism( { output: Voltage -> /* output is actually radians per second, but SysId only supports "volts" */ - setControl(m_rotationCharacterization.withRotationalRate(output.`in`(Units.Volts)))/* also log the requested output for SysId */ + setControl(m_rotationCharacterization.withRotationalRate(output.`in`(Units.Volts))) /* also log the requested output for SysId */ SignalLogger.writeDouble("Rotational_Rate", output.`in`(Units.Volts)) - }, null, this - ) + }, + null, + this, + ), ) /* The SysId routine to test */ @@ -126,7 +131,8 @@ class CommandSwerveDrivetrain : SwerveDrivetrain, Subsystem { * @param modules Constants for each specific module */ constructor(drivetrainConstants: SwerveDrivetrainConstants, vararg modules: SwerveModuleConstants?) : super( - drivetrainConstants, *modules + drivetrainConstants, + *modules, ) { if (Utils.isSimulation()) { startSimThread() @@ -176,11 +182,17 @@ class CommandSwerveDrivetrain : SwerveDrivetrain, Subsystem { * @param modules Constants for each specific module */ constructor( - drivetrainConstants: SwerveDrivetrainConstants, odometryUpdateFrequency: Double, - odometryStandardDeviation: Matrix, visionStandardDeviation: Matrix, + drivetrainConstants: SwerveDrivetrainConstants, + odometryUpdateFrequency: Double, + odometryStandardDeviation: Matrix, + visionStandardDeviation: Matrix, vararg modules: SwerveModuleConstants?, ) : super( - drivetrainConstants, odometryUpdateFrequency, odometryStandardDeviation, visionStandardDeviation, *modules + drivetrainConstants, + odometryUpdateFrequency, + odometryStandardDeviation, + visionStandardDeviation, + *modules, ) { if (Utils.isSimulation()) { startSimThread() @@ -192,24 +204,24 @@ class CommandSwerveDrivetrain : SwerveDrivetrain, Subsystem { try { val config = RobotConfig.fromGUISettings() AutoBuilder.configure( - { state.Pose }, // Supplier of current robot pose - this::resetPose, // Consumer for seeding pose against auto - { state.Speeds }, // Supplier of current robot speeds + { state.Pose }, // Supplier of current robot pose + this::resetPose, // Consumer for seeding pose against auto + { state.Speeds }, // Supplier of current robot speeds // Consumer of ChassisSpeeds and feedforwards to drive the robot { speeds: ChassisSpeeds?, feedforwards: DriveFeedforwards -> setControl( m_applyRobotSpeeds.withSpeeds(speeds) .withWheelForceFeedforwardsX(feedforwards.robotRelativeForcesXNewtons()) - .withWheelForceFeedforwardsY(feedforwards.robotRelativeForcesYNewtons()) + .withWheelForceFeedforwardsY(feedforwards.robotRelativeForcesYNewtons()), ) }, PPHolonomicDriveController( - PIDConstants(0.5, 0.0, 0.0), // PID constants for translation - PIDConstants(5.0, 0.0, 0.0) // PID constants for rotation + PIDConstants(0.5, 0.0, 0.0), // PID constants for translation + PIDConstants(5.0, 0.0, 0.0), // PID constants for rotation ), - config, // Assume the path needs to be flipped for Red vs Blue, this is normally the case + config, // Assume the path needs to be flipped for Red vs Blue, this is normally the case { DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red }, - this // Subsystem for requirements + this, // Subsystem for requirements ) } catch (ex: Exception) { DriverStation.reportError("Failed to load PathPlanner config and configure AutoBuilder", ex.stackTrace) @@ -254,7 +266,8 @@ class CommandSwerveDrivetrain : SwerveDrivetrain, Subsystem { val field: RectanglePoseArea = RectanglePoseArea(Translation2d(0.0, 0.0), Translation2d(16.54, 8.02)) - override fun periodic() {/* + override fun periodic() { + /* * Periodically try to apply the operator perspective. * If we haven't applied the operator perspective before, then we should apply it regardless of DS state. * This allows us to correct the perspective in case the robot code restarts mid-match. @@ -264,8 +277,11 @@ class CommandSwerveDrivetrain : SwerveDrivetrain, Subsystem { if (!m_hasAppliedOperatorPerspective || DriverStation.isDisabled()) { DriverStation.getAlliance().ifPresent { allianceColor: Alliance -> setOperatorPerspectiveForward( - if (allianceColor == Alliance.Red) kRedAlliancePerspectiveRotation - else kBlueAlliancePerspectiveRotation + if (allianceColor == Alliance.Red) { + kRedAlliancePerspectiveRotation + } else { + kBlueAlliancePerspectiveRotation + }, ) m_hasAppliedOperatorPerspective = true } @@ -277,19 +293,17 @@ class CommandSwerveDrivetrain : SwerveDrivetrain, Subsystem { if (left !== null) { var dist = VisionSubsystem.instance.getLeftResult()?.bestTarget?.bestCameraToTarget?.translation?.getDistance(Translation3d()) var confidence = 1 - ((dist!! - 1) / 6) // 1 - ((dist - min) / range) - if(field.isPoseWithinArea(left.estimatedPose.toPose2d())) { + if (field.isPoseWithinArea(left.estimatedPose.toPose2d())) { addVisionMeasurement(left.estimatedPose.toPose2d(), left.timestampSeconds, VecBuilder.fill(confidence, confidence, 0.01)) // [x, y, theta] } } if (right !== null) { var dist = VisionSubsystem.instance.getRightResult()?.bestTarget?.bestCameraToTarget?.translation?.getDistance(Translation3d()) var confidence = 1 - ((dist!! - 1) / 6) // 1 - ((dist - min) / range) - if(field.isPoseWithinArea(right.estimatedPose.toPose2d())) { + if (field.isPoseWithinArea(right.estimatedPose.toPose2d())) { addVisionMeasurement(right.estimatedPose.toPose2d(), right.timestampSeconds, VecBuilder.fill(confidence, confidence, 0.01)) // [x, y, theta] } } - - } private fun startSimThread() { @@ -329,8 +343,6 @@ class CommandSwerveDrivetrain : SwerveDrivetrain, Subsystem { .withRotationalDeadband(0.0).withRotationalRate(thetaController.calculate(angle.asDouble) * 2 * PI) .withVelocityX(0.0).withVelocityY(0.0) }.ignoringDisable(true).addRequirements(this) - - } } }