Skip to content

Commit

Permalink
yeet hungarian notation & rename OperatorConstants
Browse files Browse the repository at this point in the history
  • Loading branch information
willitcode committed Jan 23, 2024
1 parent 9ef5a10 commit 6a38911
Show file tree
Hide file tree
Showing 3 changed files with 13 additions and 12 deletions.
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
}
17 changes: 8 additions & 9 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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();
Expand All @@ -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() {
Expand All @@ -79,31 +78,31 @@ public static double scaleAxis(double axis) {
}

public static double getControllerLeftXAxis() {
return m_driverController.getLeftX();
return driverController.getLeftX();
}

public static double getScaledControllerLeftXAxis() {
return scaleAxis(getControllerLeftXAxis());
}

public static double getControllerLeftYAxis() {
return m_driverController.getLeftY();
return driverController.getLeftY();
}

public static double getScaledControllerLeftYAxis() {
return scaleAxis(getControllerLeftYAxis());
}

public static double getControllerRightXAxis() {
return m_driverController.getRightX();
return driverController.getRightX();
}

public static double getScaledControllerRightXAxis() {
return scaleAxis(getControllerRightXAxis());
}

public static double getControllerRightYAxis() {
return m_driverController.getRightY();
return driverController.getRightY();
}

public static double getScaledControllerRightYAxis() {
Expand Down
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/subsystems/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -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 */
Expand Down

0 comments on commit 6a38911

Please sign in to comment.