From 296279b13ad4b54245095ce3c2850d9aac13b2ba Mon Sep 17 00:00:00 2001 From: "deepsource-autofix[bot]" <62050782+deepsource-autofix[bot]@users.noreply.github.com> Date: Tue, 22 Oct 2024 20:28:53 +0000 Subject: [PATCH] style: format code with Ktlint This commit fixes the style issues introduced in 6c4c746 according to the output from Ktlint. Details: https://github.com/Bearbots6964/FRC2024-offseason/pull/2 --- .../frc/robot/generated/TunerConstants.kt | 36 +++++++++++-------- .../java/frc/robot/subsystems/ArmSubsystem.kt | 13 ++++--- .../subsystems/vision/VisionSubsystem.kt | 27 +++++++------- 3 files changed, 41 insertions(+), 35 deletions(-) diff --git a/src/main/java/frc/robot/generated/TunerConstants.kt b/src/main/java/frc/robot/generated/TunerConstants.kt index b837b6c..111ad1a 100755 --- a/src/main/java/frc/robot/generated/TunerConstants.kt +++ b/src/main/java/frc/robot/generated/TunerConstants.kt @@ -45,7 +45,7 @@ object TunerConstants { CurrentLimitsConfigs() // Swerve azimuth does not require much torque output, so we can set a relatively low // stator current limit to help avoid brownouts without impacting performance. .withStatorCurrentLimit(60.0) // TODO originally 60 - .withStatorCurrentLimitEnable(true) + .withStatorCurrentLimitEnable(true), ) private val cancoderInitialConfigs = CANcoderConfiguration() @@ -70,7 +70,6 @@ object TunerConstants { private const val kCANbusName = "rio" private const val kPigeonId = 30 - // These are only used for simulation private const val kSteerInertia = 0.00001 private const val kDriveInertia = 0.001 @@ -104,7 +103,6 @@ object TunerConstants { .withSteerMotorInitialConfigs(steerInitialConfigs) .withCANcoderInitialConfigs(cancoderInitialConfigs) - // Front Left private const val kFrontLeftDriveMotorId = 6 private const val kFrontLeftSteerMotorId = 7 @@ -145,17 +143,16 @@ object TunerConstants { private const val kBackRightXPosInches = -12.125 private const val kBackRightYPosInches = -12.125 - private val FrontLeft: SwerveModuleConstants = ConstantCreator.createModuleConstants( kFrontLeftSteerMotorId, kFrontLeftDriveMotorId, kFrontLeftEncoderId, kFrontLeftEncoderOffset, Units.inchesToMeters( - kFrontLeftXPosInches + kFrontLeftXPosInches, ), Units.inchesToMeters(kFrontLeftYPosInches), - kInvertLeftSide + kInvertLeftSide, ) .withSteerMotorInverted(kFrontLeftSteerInvert) private val FrontRight: SwerveModuleConstants = ConstantCreator.createModuleConstants( @@ -164,16 +161,22 @@ object TunerConstants { kFrontRightEncoderId, kFrontRightEncoderOffset, Units.inchesToMeters( - kFrontRightXPosInches + kFrontRightXPosInches, ), Units.inchesToMeters(kFrontRightYPosInches), - kInvertRightSide + kInvertRightSide, ) .withSteerMotorInverted(kFrontRightSteerInvert) private val BackLeft: SwerveModuleConstants = ConstantCreator.createModuleConstants( - kBackLeftSteerMotorId, kBackLeftDriveMotorId, kBackLeftEncoderId, kBackLeftEncoderOffset, Units.inchesToMeters( - kBackLeftXPosInches - ), Units.inchesToMeters(kBackLeftYPosInches), kInvertLeftSide + kBackLeftSteerMotorId, + kBackLeftDriveMotorId, + kBackLeftEncoderId, + kBackLeftEncoderOffset, + Units.inchesToMeters( + kBackLeftXPosInches, + ), + Units.inchesToMeters(kBackLeftYPosInches), + kInvertLeftSide, ) .withSteerMotorInverted(kBackLeftSteerInvert) private val BackRight: SwerveModuleConstants = ConstantCreator.createModuleConstants( @@ -182,15 +185,18 @@ object TunerConstants { kBackRightEncoderId, kBackRightEncoderOffset, Units.inchesToMeters( - kBackRightXPosInches + kBackRightXPosInches, ), Units.inchesToMeters(kBackRightYPosInches), - kInvertRightSide + kInvertRightSide, ) .withSteerMotorInverted(kBackRightSteerInvert) val DriveTrain: CommandSwerveDrivetrain = CommandSwerveDrivetrain( - DrivetrainConstants, FrontLeft, - FrontRight, BackLeft, BackRight + DrivetrainConstants, + FrontLeft, + FrontRight, + BackLeft, + BackRight, ) } diff --git a/src/main/java/frc/robot/subsystems/ArmSubsystem.kt b/src/main/java/frc/robot/subsystems/ArmSubsystem.kt index 62e97cc..fab72ea 100644 --- a/src/main/java/frc/robot/subsystems/ArmSubsystem.kt +++ b/src/main/java/frc/robot/subsystems/ArmSubsystem.kt @@ -25,10 +25,13 @@ object ArmSubsystem : Subsystem { fun getCommand(joystickTriggerValue: () -> Double): Command { return run { - if (joystickTriggerValue.invoke() > 0.1) extend(joystickTriggerValue.invoke()) else if (joystickTriggerValue.invoke() < -0.1) retract( - -joystickTriggerValue.invoke() - ) + if (joystickTriggerValue.invoke() > 0.1) { + extend(joystickTriggerValue.invoke()) + } else if (joystickTriggerValue.invoke() < -0.1) { + retract( + -joystickTriggerValue.invoke(), + ) + } } - } -} \ No newline at end of file +} diff --git a/src/main/java/frc/robot/subsystems/vision/VisionSubsystem.kt b/src/main/java/frc/robot/subsystems/vision/VisionSubsystem.kt index 3b8c52a..e22e8a5 100644 --- a/src/main/java/frc/robot/subsystems/vision/VisionSubsystem.kt +++ b/src/main/java/frc/robot/subsystems/vision/VisionSubsystem.kt @@ -1,25 +1,25 @@ package frc.robot.subsystems.vision -import edu.wpi.first.wpilibj2.command.SubsystemBase import edu.wpi.first.math.geometry.Rotation2d +import edu.wpi.first.wpilibj2.command.SubsystemBase import org.photonvision.PhotonCamera -import org.photonvision.PhotonUtils import org.photonvision.targeting.PhotonTrackedTarget -class VisionSubsystem : SubsystemBase(){ - private var camera : PhotonCamera = PhotonCamera("ShitCam") +class VisionSubsystem : SubsystemBase() { + private var camera: PhotonCamera = PhotonCamera("ShitCam") private lateinit var rot: Rotation2d private var countWithoutMeasurement: Int = 0 - - override fun periodic(){ + override fun periodic() { // This method will be called once per scheduler run var result = camera.getLatestResult() - if(result.hasTargets()){ - var target : PhotonTrackedTarget = result.getBestTarget() + if (result.hasTargets()) { + var target: PhotonTrackedTarget = result.getBestTarget() rot = Rotation2d.fromDegrees(target.yaw) countWithoutMeasurement = 0 - } else countWithoutMeasurement++ + } else { + countWithoutMeasurement++ + } if (countWithoutMeasurement > 25) { // method called every 20 ms, // so 25 * 20 = 500 ms without a target before setting rotation to 0 @@ -27,11 +27,8 @@ class VisionSubsystem : SubsystemBase(){ } } - //returns angle to nearest note relative to the front of the robot - fun getNearestRotation() : Rotation2d { - + // returns angle to nearest note relative to the front of the robot + fun getNearestRotation(): Rotation2d { return rot } - - -} \ No newline at end of file +}