From 170d34ff27a189ec08ba2bf372f5668fea0dfe8d Mon Sep 17 00:00:00 2001 From: Nilesh Agarwalla Date: Fri, 5 Apr 2024 15:29:39 -0400 Subject: [PATCH] spotlessApply --- .../java/frc/robot/config/RobotConfig.java | 2 +- .../java/frc/robot/subsystems/drive/Drive.java | 3 +-- .../frc/robot/subsystems/drive/DriveIO.java | 18 ++++++++++++------ .../subsystems/drive/DriveSwerveYAGSL.java | 1 - .../java/frc/robot/util/DevilBotState.java | 2 +- 5 files changed, 15 insertions(+), 11 deletions(-) diff --git a/src/main/java/frc/robot/config/RobotConfig.java b/src/main/java/frc/robot/config/RobotConfig.java index d05ae82c..e9352f35 100644 --- a/src/main/java/frc/robot/config/RobotConfig.java +++ b/src/main/java/frc/robot/config/RobotConfig.java @@ -57,7 +57,7 @@ public static class DriveConstants { public static double blueSpeakerX = 0.14; public static double speakerY = 5.53; - public static double redSpeakerX = 16.54-0.14; + public static double redSpeakerX = 16.54 - 0.14; } public static class ArmConstants { diff --git a/src/main/java/frc/robot/subsystems/drive/Drive.java b/src/main/java/frc/robot/subsystems/drive/Drive.java index b7c02136..912fbdbc 100644 --- a/src/main/java/frc/robot/subsystems/drive/Drive.java +++ b/src/main/java/frc/robot/subsystems/drive/Drive.java @@ -1,13 +1,12 @@ package frc.robot.subsystems.drive; -import java.util.Optional; - import edu.wpi.first.math.Matrix; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.kinematics.ChassisSpeeds; import edu.wpi.first.math.numbers.N1; import edu.wpi.first.math.numbers.N3; import edu.wpi.first.wpilibj2.command.Command; +import java.util.Optional; public interface Drive { /** diff --git a/src/main/java/frc/robot/subsystems/drive/DriveIO.java b/src/main/java/frc/robot/subsystems/drive/DriveIO.java index 67e8ad63..0336afe2 100644 --- a/src/main/java/frc/robot/subsystems/drive/DriveIO.java +++ b/src/main/java/frc/robot/subsystems/drive/DriveIO.java @@ -3,7 +3,6 @@ import edu.wpi.first.math.geometry.Pose2d; import frc.robot.config.RobotConfig.DriveConstants; import frc.robot.util.DevilBotState; - import org.littletonrobotics.junction.AutoLog; import swervelib.SwerveDrive; @@ -23,11 +22,18 @@ public void updateInputs(DriveIOInputs inputs, SwerveDrive swerveDrive) { inputs.poseX = inputs.pose.getTranslation().getX(); inputs.poseY = inputs.pose.getTranslation().getY(); inputs.poseRotInDegrees = inputs.pose.getRotation().getDegrees(); - if(!DevilBotState.isRedAlliance()){ - inputs.distanceFromSpeaker = Math.sqrt(Math.pow(inputs.poseX - DriveConstants.blueSpeakerX,2)+Math.pow(inputs.poseY - DriveConstants.speakerY,2)); - } else{ - inputs.distanceFromSpeaker = Math.sqrt(Math.pow(inputs.poseX - DriveConstants.redSpeakerX,2)+Math.pow(inputs.poseY - DriveConstants.speakerY,2)); - } ; + if (!DevilBotState.isRedAlliance()) { + inputs.distanceFromSpeaker = + Math.sqrt( + Math.pow(inputs.poseX - DriveConstants.blueSpeakerX, 2) + + Math.pow(inputs.poseY - DriveConstants.speakerY, 2)); + } else { + inputs.distanceFromSpeaker = + Math.sqrt( + Math.pow(inputs.poseX - DriveConstants.redSpeakerX, 2) + + Math.pow(inputs.poseY - DriveConstants.speakerY, 2)); + } + ; } // Other methods for controlling the drive subsystem... diff --git a/src/main/java/frc/robot/subsystems/drive/DriveSwerveYAGSL.java b/src/main/java/frc/robot/subsystems/drive/DriveSwerveYAGSL.java index d8a4541e..031152c8 100644 --- a/src/main/java/frc/robot/subsystems/drive/DriveSwerveYAGSL.java +++ b/src/main/java/frc/robot/subsystems/drive/DriveSwerveYAGSL.java @@ -16,7 +16,6 @@ import frc.robot.util.DevilBotState; import java.io.File; import java.util.Optional; - import org.littletonrobotics.junction.AutoLogOutput; import org.littletonrobotics.junction.Logger; import swervelib.SwerveDrive; diff --git a/src/main/java/frc/robot/util/DevilBotState.java b/src/main/java/frc/robot/util/DevilBotState.java index 40a17c6d..da296162 100644 --- a/src/main/java/frc/robot/util/DevilBotState.java +++ b/src/main/java/frc/robot/util/DevilBotState.java @@ -185,7 +185,7 @@ public static Optional getArmAngleToTarget() { return armAngle; } else { - distanceToTarget =RobotConfig.drive.getDistanceFromSpeaker(); + distanceToTarget = RobotConfig.drive.getDistanceFromSpeaker(); if (distanceToTarget.isPresent()) { Optional armAngle = RobotConfig.instance.getArmAngleFromDistance(distanceToTarget.get());