From 6a3891142ccc0a7815df93ddab29d6ccb00c50a3 Mon Sep 17 00:00:00 2001 From: willitcode <91231142+willitcode@users.noreply.github.com> Date: Mon, 22 Jan 2024 19:48:31 -0600 Subject: [PATCH] yeet hungarian notation & rename OperatorConstants --- src/main/java/frc/robot/Constants.java | 4 ++-- src/main/java/frc/robot/RobotContainer.java | 17 ++++++++--------- src/main/java/frc/robot/subsystems/Drive.java | 4 +++- 3 files changed, 13 insertions(+), 12 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index c4251950..05183a7f 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -19,7 +19,7 @@ * constants are needed, to reduce verbosity. */ public final class Constants { - public static class OperatorConstants { - public static final int kDriverControllerPort = 0; + public static class Controllers { + public static final int DRIVER_CONTROLLER_PORT = 0; } } diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index dfff026a..6b1d93b1 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -14,7 +14,6 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; -import frc.robot.Constants.OperatorConstants; import frc.robot.commands.DriveFieldOriented; import frc.robot.commands.DriveRobotOriented; import frc.robot.commands.EnterXMode; @@ -54,8 +53,8 @@ public class RobotContainer { /* The CommandXboxController instance must be static to allow the getter methods for its axes * to work. */ - public static CommandXboxController m_driverController = - new CommandXboxController(OperatorConstants.kDriverControllerPort); + public static CommandXboxController driverController = + new CommandXboxController(Constants.Controllers.DRIVER_CONTROLLER_PORT); public RobotContainer() { configureBindings(); @@ -64,9 +63,9 @@ public RobotContainer() { } private void configureBindings() { - m_driverController.leftStick().toggleOnTrue(driveFieldOriented); + driverController.leftStick().toggleOnTrue(driveFieldOriented); - m_driverController.x().onTrue(enterXMode); + driverController.x().onTrue(enterXMode); } public Command getAutonomousCommand() { @@ -79,7 +78,7 @@ public static double scaleAxis(double axis) { } public static double getControllerLeftXAxis() { - return m_driverController.getLeftX(); + return driverController.getLeftX(); } public static double getScaledControllerLeftXAxis() { @@ -87,7 +86,7 @@ public static double getScaledControllerLeftXAxis() { } public static double getControllerLeftYAxis() { - return m_driverController.getLeftY(); + return driverController.getLeftY(); } public static double getScaledControllerLeftYAxis() { @@ -95,7 +94,7 @@ public static double getScaledControllerLeftYAxis() { } public static double getControllerRightXAxis() { - return m_driverController.getRightX(); + return driverController.getRightX(); } public static double getScaledControllerRightXAxis() { @@ -103,7 +102,7 @@ public static double getScaledControllerRightXAxis() { } public static double getControllerRightYAxis() { - return m_driverController.getRightY(); + return driverController.getRightY(); } public static double getScaledControllerRightYAxis() { diff --git a/src/main/java/frc/robot/subsystems/Drive.java b/src/main/java/frc/robot/subsystems/Drive.java index 90767257..0d88c0dd 100644 --- a/src/main/java/frc/robot/subsystems/Drive.java +++ b/src/main/java/frc/robot/subsystems/Drive.java @@ -25,12 +25,14 @@ public class Drive extends SubsystemBase { /** Creates a new Drive. */ public Drive() { + /* Try-catch because otherwise the compiler tries to anticipate runtime errors and throws a + * compiletime error for a missing file even though it shouldn't + */ try { drive = new SwerveParser(new File(Filesystem.getDeployDirectory(), "swerve")) .createSwerveDrive(Units.feetToMeters(14.5)); } catch (IOException e) { - // TODO Auto-generated catch block e.printStackTrace(); } /* setting the motors to brake mode */